We are trying to use YAGSL version 2025.2.1, but we are getting CAN errors from our pigeon 2.0 and we see nothing reported from the YAGSL logging.
The CAN errors are:
On Phoenix 5 firmware (2022):
- ERROR -3 CTR: CAN frame not received/too-stale. Pigeon IMU 2 Get Fused Heading
- ERROR -3 CTR: CAN frame not received/too-stale. Pigeon IMU 2 GetFusedHeading
These errors happen within 100ms of each other, and repeat about every 3 seconds.
On Phoenix 6 firmware (2025):
- ERROR -3 CTR: CAN frame not received/too-stale. Pigeon IMU 2 Get 6d Quaternion
- ERROR -3 CTR: CAN frame not received/too-stale. Pigeon IMU 2 Get Fused Heading
- ERROR 103 CTR: Firm Vers could not be retrieved. Use Phoenix Tuner X to check that the device is running Phoenix 5 firmware (22.X), the device ID is correct, the specified CAN bus is correct, and the device is powered.
These errors also all happen within 100ms of each other, and repeat about every 3 seconds.
Additionally, even though the verbosity is set to LOW, all of the fields logged by YAGSL show up as blank in AdvantageScope and Shuffleboard.
In order to try and test everything, I also deployed the AdvantageKit 4.1.0 Spark Swerve template and got no can errors for anything while disabled after changing the CAN Ids. However, this was a quick fix so I did not change the code to use CANcoders instead of REV abosolute encoders. I did not enable the bot with this code.
Our team is using MK4c swerve modules with VORTEX drive motors, NEO 1.1 steering motors, and CANcoders. Our gyro is a CTRE pigeon 2.0.
Gyro YAGSL config JSON
{
"imu": {
"type": "pigeon",
"id": 2,
"canbus": "rio"
},
"invertedIMU": false,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
We got CAN errors from the gyro when using null for the gyro can bus and when using “rio” for the gyro can bus.
Drive subsystem code
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.subsystems.Drive;
import java.io.File;
import java.io.IOException;
import java.util.function.DoubleSupplier;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import swervelib.SwerveDrive;
import swervelib.parser.SwerveParser;
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
public class SillyDrive extends SubsystemBase {
// https://docs.yagsl.com/configuring-yagsl/code-setup
private File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(), "swerve");
private SwerveDrive swerveDrive;
public SillyDrive() {
/*
* !_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!
* TELEMETRY - SET THIS TO LOW FOR DEBUGGING, AND HIGH FOR FASTER CODE
* !_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!_!
*/
SwerveDriveTelemetry.verbosity = TelemetryVerbosity.LOW;
// Swerve init - https://docs.yagsl.com/configuring-yagsl/code-setup
try{
swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(DriveConstants.maximumModuleSpeed);
}
catch (IOException e) {
DriverStation.reportError("Swerve config not found: " + e.toString(), true);
}
//https://github.com/BroncBotz3481/YAGSL-Example/blob/main/src/main/java/frc/robot/subsystems/swervedrive/SwerveSubsystem.java
//Heading correction should only be used while controlling the robot via angle.
swerveDrive.setHeadingCorrection(false);
//!SwerveDriveTelemetry.isSimulation); // Disables cosine compensation for simulations since it causes discrepancies not seen in real life.
swerveDrive.setCosineCompensator(false);
//Correct for skew that gets worse as angular velocity increases. Start with a coefficient of 0.1.
swerveDrive.setAngularVelocityCompensation(true, true, 0.1);
// Enable if you want to resynchronize your absolute encoders and motor encoders periodically when they are not moving.
swerveDrive.setModuleEncoderAutoSynchronize(false, 1);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
public void drive(double translationX, double translationY, double rotation, boolean isFieldRelative, boolean isOpenLoop){
swerveDrive.drive(new Translation2d(translationX * swerveDrive.getMaximumChassisVelocity(),
translationY * swerveDrive.getMaximumChassisVelocity()),
rotation * swerveDrive.getMaximumChassisAngularVelocity(),
isFieldRelative,
isOpenLoop // Ususally false
);
}
public Command humanDriveCommand(DoubleSupplier xInput, DoubleSupplier yInput, DoubleSupplier thetaInput){
return new RunCommand(
() -> {
this.drive(
xInput.getAsDouble(),
yInput.getAsDouble(),
thetaInput.getAsDouble(),
true,
false
);
}
, this);
}
}
Robot container code
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.Constants.OIConstants;
//import frc.robot.subsystems.Drive.Drive;
import frc.robot.subsystems.Drive.SillyDrive;
import frc.robot.subsystems.Drive.SwerveIO;
import frc.robot.subsystems.Drive.SwerveIOSpark;
public class RobotContainer {
private SillyDrive drivetrain;
public RobotContainer() {
// switch(Constants.currentMode){
// case REAL:
// drivetrain = Drive.initialize(new SwerveIOSpark());
// break;
// case SIM:
// //drivetrain = new Drive();
// break;
// default:
// drivetrain = new Drive(new SwerveIO() {});
// break;
// }
//drivetrain = Drive.initialize(new SwerveIOSpark());
drivetrain = new SillyDrive();
drivetrain.setDefaultCommand(drivetrain.humanDriveCommand(
OIConstants.driverController::getLeftX,
OIConstants.driverController::getLeftY,
OIConstants.driverController::getRightX
));
configureBindings();
}
private void configureBindings() {}
public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
}
}
As you can probably see, we tried to add AdvantageKit, but commented it out in the RobotContainer so we could get the swerve working without it first. The Robot.java file still initializes the logger.
Robot.java code
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot;
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends LoggedRobot {
private Command m_autonomousCommand;
private final RobotContainer m_robotContainer;
public Robot() {
//LOGGER GOES FIRST
Logger.recordMetadata("ProjectName", "MyProject"); // Set a metadata value
if (isReal()) {
Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs")
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging
} else {
setUseTiming(false); // Run as fast as possible
String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user)
Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log
Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save outputs to a new log
}
Logger.start();
m_robotContainer = new RobotContainer();
}
@Override
public void robotPeriodic() {
CommandScheduler.getInstance().run();
}
@Override
public void disabledInit() {}
@Override
public void disabledPeriodic() {}
@Override
public void disabledExit() {}
@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
}
}
@Override
public void autonomousPeriodic() {}
@Override
public void autonomousExit() {}
@Override
public void teleopInit() {
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
}
@Override
public void teleopPeriodic() {}
@Override
public void teleopExit() {}
@Override
public void testInit() {
CommandScheduler.getInstance().cancelAll();
}
@Override
public void testPeriodic() {}
@Override
public void testExit() {}
}
Any help would be much appreciated. Thank you in advance!