Yet Another Generic Swerve Library (YAGSL) v1 Release

Hello World!

After a year of beta testing and a late start to 2024. YAGSL is finally able to be released into the world as the first version. There are a few things that didn’t quite make it into this release like a C++ port that I initially wanted to do and still plan to do. I have consolidated the documentation and hope you enjoy the new format!

YAGSL is a Generic Swerve Library (AN ACTUAL LIBRARY!) that aims to simplify the process of creating a comprehensive and complete SwerveDrive with best practices from MANY SwerveDrive examples. YAGSL supports pretty much every swerve drive configuration possible and if there is an issue we will address it as soon as possible and credit discoveries.

YAGSL is designed so you can just copy over your code onto a robot then configure the JSON files and your program will just work. If you develop multiple robots this could be a major benefit because your competition robot and practice robot can have the same codebase without changing anything.

Documentation- Welcome to Yet Another Swerve Document - YAGSL
Example Code- GitHub - BroncBotz3481/YAGSL-Example: Yet Another General Swerve Library Example Project
VendorDep- https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json
Configuration Generator- YAGSL Tuning Webpage

A quick overview of YAGSL features are:

  • Uses motor controller PID exclusively.
  • Data for each swerve module.
  • Compatible with Advantage Scope swerve widget.
  • Compatible with FRC Web Components.
  • Support for TalonFX, SparkFlex, and SparkMax without changing any of the code base.
  • An actual library as opposed to template code.
  • Documentation , yes even javadocs .
  • Most absolute encoders (even discontinued ones!) are supported!
  • Does not require a CommandBased project and could be implemented in a TimedRobot.
  • Advanced tuning for motor controller output limits and supply amps.
  • Simulation support.
  • An easy configuration webpage!
  • PathPlanner implemented.
  • PhotonVision support.
  • Tuner X Swerve Generator is recommended if you have compatible components.



This thread will serve as another way to report issue’s if you do not submit one via github. I review every pull request too and provide feedback.

This work couldn’t have been possible without the support of the community and contributors!

Developers:
@nstrike
@Technologyman00

Contributors:
@gdgr
@BlueEpiphone
@bhall-ctre
and many more!

I hope everyone enjoys this!
Thank you!

If you would to support @nstrike in building his own swerve bot (not with a team) you can donate here.

26 Likes

A nice recap on how easy it is to drive is the following lines of code which can be put in a Subsystem

  /**
   * Command to drive the robot using translative values and heading as a setpoint.
   *
   * @param translationX Translation in the X direction.
   * @param translationY Translation in the Y direction.
   * @param headingX     Heading X to calculate angle of the joystick.
   * @param headingY     Heading Y to calculate angle of the joystick.
   * @return Drive command.
   */
  public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier headingX,
                              DoubleSupplier headingY)
  {
    return run(() -> {
      double xInput = Math.pow(translationX.getAsDouble(), 3); // Smooth controll out
      double yInput = Math.pow(translationY.getAsDouble(), 3); // Smooth controll out
      // Make the robot move
      driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(xInput, yInput,
                                                                      headingX.getAsDouble(),
                                                                      headingY.getAsDouble(),
                                                                      swerveDrive.getYaw().getRadians(),
                                                                      swerveDrive.getMaximumVelocity()));
    });
  }

  /**
   * Command to drive the robot using translative values and heading as angular velocity.
   *
   * @param translationX     Translation in the X direction.
   * @param translationY     Translation in the Y direction.
   * @param angularRotationX Rotation of the robot to set
   * @return Drive command.
   */
  public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX)
  {
    return run(() -> {
      // Make the robot move
      swerveDrive.drive(new Translation2d(translationX.getAsDouble() * swerveDrive.getMaximumVelocity(),
                                          translationY.getAsDouble() * swerveDrive.getMaximumVelocity()),
                        angularRotationX.getAsDouble() * swerveDrive.getMaximumAngularVelocity(),
                        true,
                        false);
    });
  }
2 Likes

I’ve found it’s compatible with most of Advantage Scope! 2D field or 3D field work great!

1 Like

Congratulations @nstrike and the rest of the contributors who have aided in the development to your first initial release!

Running into our own issues with our original template, we were really worried about our swerve drive… until we saw the original announcement for this project!

Running it in the 2023 season, we never had a software failure on our swerve drive, with all of instances of it slipping up being 100% mechanical issues :slight_smile: .

We are so impressed that we have decided to make it our de-facto solution for years to come when it comes to our swerve drive. Thank you for all that you do, keep it up.

Hats off to all of you!

7 Likes

Did it happen to anyone that only the drive motor works? The angle doesn’t respond to the code however it does work in phoenix.
Thats my code: ( basically the example ) GitHub - GlueGunGlitter/Crescendo2024

Use these PIDF values for your angle motor

{
  "drive": {
    "p": 1,
    "i": 0,
    "d": 0,
    "f": 0,
    "iz": 0
  },
  "angle": {
    "p": 50,
    "i": 0,
    "d": 0.32,
    "f": 0,
    "iz": 0
  }
}

I had to revert to an earlier state where I use the high values bc the high values give more range.

I also note this on the configuration page of documentation.

Hello, I think the idea of these new libraries and the idea of YAGSL are fantastic, but we had some problems when we tried to manage it, each module starts to move in all directions without someone managing it from the control and it doesn’t even take a signal from the control, using the code. example of YAGSL but this situation always happens. I wanted to ask if there is a way to solve this, we use the example as it is, using for each module a falcon for drive and a neo for angle.

I just wrote some documentation about this today. Have you seen it?

tl;dr It sounds like you need to invert your angle motors

2 Likes

Hi! Thank you for creating and maintaining YAGSL. We’re trying to get swerve going for the first time this year after using tank and mecanum for years. We’re starting with the YAGSL example project to get to a driving base so we understand what we’re doing.

Here’s our set up:

  • Java
  • Robo Rio 2 (CAN bus)
  • Rev PDB (CAN termination)
  • Mk4i modules with cancoders and neos
  • SparkMax controllers
  • Pigeon 2 IMU

Device IDs are 1-14 with 14 being the PDP. We’ve confirmed the IDs are set correctly for each device using the Rev Hardware Client and Phoenix Tuner X. All devices say they have the latest firmware. The Rio 2 also has the latest image.

We updated the JSON tree in the deploy directory with the YAGSL configs for the MK4i neo configs in the YAGSL-Config Repo.

Our frame is a 29"x29" square. The pigeon 2 is in the center of the robot. We updated the copied configs to our device ids and changed the canbus property in swervedrive.json to “rio”.

The code builds without error and deploys but then we get a flood of messages on the console. If we enable it, the back left angle motor spins on its own. If we push the joystick up, the left drive motors spin.

Among the errors we’re getting on the console are “failure to configure motor 2” (on several different motors), “CAN frame not received/too-stale”, “cancoder 9 () Status Signal MagnetHealth”. There are others too, but from experience we know a lot of different errors can cascade from a single issue. I have attached the RioLog json export.

I feel like we’re really close as this library is so simple to configure and well designed, but I can’t tell if it’s a configuration or hardware issue and need help troubleshooting. The swerve stack is more complicated than what we’ve dealt with in the past.

TIA!

RioLog.json (257.7 KB)

We are working to get YAGSL working with Pathplanner and other than PID tuning it generally works fine, but the robot horizontal translation is flipped. When we command a path that moves right it moves left and vice versa. Do you think you would be able to help with this, or does it sound like a Pathplanner generation issue?

To calculate the robot speeds we get target speeds using the holonomic controller from Pathplanner on a sample from a timer and then follow them using the .drive method from YAGSL. I believe this is correct.

Code: Robocats2024/src/main/java/frc/team1699/subsystems/Drive.java at kevin-yagsl · FIRST-Team-1699/Robocats2024 · GitHub

( @alex-1699 )

Our team is having issues with our swerve using YAGSL. Our config is mk4i with neos, a navx through usb, and cancoders. We are having trouble it seems with our cancoders, we are getting all values except for the raw absolute encoder value for the offsets. I updated our cancoders all to the latest firmware. Here is our error message.

  • ********** Robot program starting **********

  • NT: Listening on NT3 port 1735, NT4 port 5810

  • NT: Got a NT4 connection from 10.35.46.226 port 50754

  • NT: CONNECTED NT4 client ‘shuffleboard@1’ (from 10.35.46.226:50754)

  • “conversionFactor”: {

  • “angle”: 28.125,

  • “drive”: 0.047286787200699704

  • }

  • NT: Got a NT3 connection from 10.35.46.102 port 33494

  • NT: CONNECTED NT3 client ‘[email protected]:33494’ (from 10.35.46.102:33494)

  • [phoenix] CANbus Failed to Connect: 3

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • [phoenix] CANbus Failed to Connect: 0

  • [phoenix] CANbus Failed to Connect: 1

  • [phoenix] CANbus Failed to Connect: 2

  • Instantiating navX-Sensor on Serial Port kUSB.

  • navX-Sensor Java library for FRC

  • Opening USB serial port to communicate with navX-Sensor.

  • navX-Sensor Connected via USB.

  • navX-Sensor Configuration Response Received.

  • navX-Sensor Connected.

  • navX-Sensor onboard startup calibration complete.

  • navX-Sensor Yaw angle auto-reset to 0.0 due to startup calibration.

  • navX-Sensor Board Type 50 (navX2-Micro (Gen 2))

  • navX-Sensor firmware version 4.0

  • Could not transmit CAN Frame.

  • Could not transmit CAN Frame.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CANCoder 3 magnetic field is less than ideal.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 3 magnetic field is less than ideal.

  • CANCoder 3 reading was faulty.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 3 reading was faulty.

  • Could not transmit CAN Frame.

  • Could not transmit CAN Frame.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CANCoder 2 magnetic field is less than ideal.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 2 magnetic field is less than ideal.

  • CANCoder 2 reading was faulty.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 2 reading was faulty.

  • Could not transmit CAN Frame.

  • Could not transmit CAN Frame.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CANCoder 1 magnetic field is less than ideal.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 1 magnetic field is less than ideal.

  • CANCoder 1 reading was faulty.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 1 reading was faulty.

  • [phoenix] Library initialization is complete.

  • [phoenix] CANbus Failed to Connect: 3

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • [phoenix] CANbus Failed to Connect: 0

  • [phoenix] CANbus Failed to Connect: 1

  • [phoenix] CANbus Failed to Connect: 2

  • Could not transmit CAN Frame.

  • Could not transmit CAN Frame.

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CANCoder 0 magnetic field is less than ideal.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 0 magnetic field is less than ideal.

  • CANCoder 0 reading was faulty.

  • Warning at swervelib.telemetry.Alert.set(Alert.java:104): CANCoder 0 reading was faulty.

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • Joystick Button 1 on port 0 not available, check if controller is plugged in

  • Warning at edu.wpi.first.wpilibj.DriverStation.reportJoystickUnpluggedWarning(DriverStation.java:1362): Joystick Button 1 on port 0 not available, check if controller is plugged in

  • [phoenix-diagnostics] Server 2024.1.0 (Jan 8 2024, 18:07:22) running on port: 1250

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • ********** Robot program startup complete **********

  • Loop time of 0.02s overrun

  • Warning at edu.wpi.first.wpilibj.IterativeRobotBase.printLoopOverrunMessage(IterativeRobotBase.java:412): Loop time of 0.02s overrun

  • CommandScheduler loop overrun

  • SwerveSubsystem.periodic(): 0.017549s
    buttons.run(): 0.034577s

  • Warning at edu.wpi.first.wpilibj.Tracer.lambda$printEpochs$0(Tracer.java:62): SwerveSubsystem.periodic(): 0.017549s

  • buttons.run(): 0.034577s

  • SmartDashboard.updateValues(): 0.021481s
    disabledInit(): 0.010054s
    robotPeriodic(): 0.161385s
    LiveWindow.updateValues(): 0.000112s
    Shuffleboard.update(): 0.009794s
    disabledPeriodic(): 0.001391s

  • Warning at edu.wpi.first.wpilibj.Tracer.lambda$printEpochs$0(Tracer.java:62): SmartDashboard.updateValues(): 0.021481s

  • disabledInit(): 0.010054s

  • robotPeriodic(): 0.161385s

  • LiveWindow.updateValues(): 0.000112s

  • Shuffleboard.update(): 0.009794s

  • disabledPeriodic(): 0.001391s

  • Joystick Button 1 on port 0 not available, check if controller is plugged in

  • Warning at edu.wpi.first.wpilibj.DriverStation.reportJoystickUnpluggedWarning(DriverStation.java:1362): Joystick Button 1 on port 0 not available, check if controller is plugged in

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • CommandScheduler loop overrun

  • [phoenix] CANbus Failed to Connect: 3

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • [phoenix] CANbus Failed to Connect: 0

  • [phoenix] CANbus Failed to Connect: 1

  • [phoenix] CANbus Failed to Connect: 2

  • Loop time of 0.02s overrun

  • Warning at edu.wpi.first.wpilibj.IterativeRobotBase.printLoopOverrunMessage(IterativeRobotBase.java:412): Loop time of 0.02s overrun

  • SmartDashboard.updateValues(): 0.038287s
    robotPeriodic(): 0.000946s
    LiveWindow.updateValues(): 0.000038s
    Shuffleboard.update(): 0.000018s
    disabledPeriodic(): 0.000352s

  • Warning at edu.wpi.first.wpilibj.Tracer.lambda$printEpochs$0(Tracer.java:62): SmartDashboard.updateValues(): 0.038287s

  • robotPeriodic(): 0.000946s

  • LiveWindow.updateValues(): 0.000038s

  • Shuffleboard.update(): 0.000018s

  • disabledPeriodic(): 0.000352s

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • Joystick Button 1 on port 0 not available, check if controller is plugged in

  • Warning at edu.wpi.first.wpilibj.DriverStation.reportJoystickUnpluggedWarning(DriverStation.java:1362): Joystick Button 1 on port 0 not available, check if controller is plugged in

  • CAN frame not received/too-stale. Check the CAN bus wiring, CAN bus utilization, and power to the device.

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • Device firmware could not be retrieved. Check that the device is running v6 firmware, the device ID is correct, the specified CAN bus is correct, and the device is powered.

  • Joystick Button 1 on port 0 not available, check if controller is plugged in

  • Warning at edu.wpi.first.wpilibj.DriverStation.reportJoystickUnpluggedWarning(DriverStation.java:1362): Joystick Button 1 on port 0 not available, check if controller is plugged in

  • Loop time of 0.02s overrun

  • Warning at edu.wpi.first.wpilibj.IterativeRobotBase.printLoopOverrunMessage(IterativeRobotBase.java:412): Loop time of 0.02s overrun

  • CommandScheduler loop overrun

  • SwerveSubsystem.periodic(): 0.000204s
    buttons.run(): 0.037935s

  • Warning at edu.wpi.first.wpilibj.Tracer.lambda$printEpochs$0(Tracer.java:62): SwerveSubsystem.periodic(): 0.000204s

  • buttons.run(): 0.037935s

  • SmartDashboard.updateValues(): 0.008681s
    robotPeriodic(): 0.071047s
    LiveWindow.updateValues(): 0.000000s
    Shuffleboard.update(): 0.000037s
    disabledPeriodic(): 0.003172s

  • Warning at edu.wpi.first.wpilibj.Tracer.lambda$printEpochs$0(Tracer.java:62): SmartDashboard.updateValues(): 0.008681s

  • robotPeriodic(): 0.071047s

  • LiveWindow.updateValues(): 0.000000s

  • Shuffleboard.update(): 0.000037s

  • disabledPeriodic(): 0.003172s

And here is a link to our code: GitHub - FRC3546/2024-Test-Robot

We are very excited about this swerve library but are hoping to get things running soon. Any help is appreciated!

This page, and the documentation is great!

2 Likes

Did you update to firmware for Phoenix 6?

Does the reset odometry method work 100% correctly? Because when running PathPlanner autos on the red alliance our robot does a full 180 throughout the entire duration of the auto when using our robot code and YAGSL example code. But on blue alliance it works as expected. This happens in both simulation and on an actual robot

Video: FRC 1806 SWAT Path Planner test.mkv - Google Drive (shows running a path on blue alliance where the path runs correctly then next it shows red alliance where path runs incorrectly)

Code: GitHub - frc1806/Crescendo-1806: FRC Team 1806's 2024 Robot Code

There is a PR i am reviewing today to fix this issue here. It will be released under 2024.5.6.1 when it gets merged. Thank you for this video though as it will be invaluable in making my determination!

1 Like

You’re welcome and thank you!

1 Like

Does YAGSL support neo vortex and spark flex? If not will it?

It does

Just as an update here. I had changed the type navx_mxp to navx_mxp_serial!

1 Like

Has anyone created a known working YAGSL configuration with SDS Mk4i, Neo, NavX Mxp, and CANANDCODERS?

Thank You