Setting Up a Swerve Drive with YAGSL for FRC#
This tutorial provides a comprehensive, step-by-step guide to setting up a swerve drive using Yet Another Generic Swerve Library (YAGSL) for FIRST Robotics Competition (FRC) projects. YAGSL is designed to simplify swerve drive implementation by providing a generic, well-documented library that works with various motor controllers and sensors, eliminating the need for custom code for each robot configuration.
1. Introduction to YAGSL#
YAGSL (Yet Another Generic Swerve Library) is a swerve drive library developed by current and former BroncBotz mentors for FRC teams. Its primary goal is to make swerve drive programming as straightforward as using a DifferentialDrive, while supporting a wide range of hardware combinations.
Key Features#
- Generic Design: Works with mixed hardware (e.g., REV SparkMax with CTRE CANCoder, TalonFX with Pigeon2, etc.)
- JSON-Based Configuration: Robot-specific settings are stored in JSON files, allowing the same code to work across different robots
- Active Maintenance: Regularly updated and community-supported
- Comprehensive Documentation: Extensive guides, examples, and troubleshooting resources
Why YAGSL?#
Unlike many swerve templates that require extensive modification, YAGSL abstracts hardware differences, so teams can focus on robot logic rather than drive code. It's particularly useful for teams with multiple robots or those using non-standard hardware combinations.
For more details, see the YAGSL Overview.
2. Prerequisites and Dependencies#
Before starting, ensure you have the following installed and configured.
Software Requirements#
- WPILib: Latest stable version for your season (2025 recommended)
- Installation guide: WPILib Setup
- REV Hardware Client 2: For configuring REV devices
- Download: REV Hardware Client
- CTRE Tuner X: For configuring CTRE devices (Phoenix 6)
- Installation: Phoenix 6 Installation
Vendor Dependencies (Vendordeps)#
YAGSL requires vendor libraries for all supported hardware, even if not used on your robot. Install these via WPILib's vendor dependency system:
- REVLib:
https://software-metadata.revrobotics.com/REVLib.json - Phoenix 6:
https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json - ReduxLib:
https://frcsdk.reduxrobotics.com/ReduxLib.json - PhotonVision (optional, for vision):
https://maven.photonvision.org/repository/internal/org/photonvision/PhotonLib-json/1.0/PhotonLib-json-1.0.json - YAGSL:
https://yet-another-software-suite.github.io/YAGSL/yagsl.json
Installation steps: 3rd Party Libraries
Hardware Knowledge#
You should know your robot's physical characteristics before configuration. See section 3 for details.
3. Hardware Requirements and Getting to Know Your Robot#
A swerve drive consists of: - Gyroscope/IMU: For heading tracking (e.g., Pigeon2, NavX, or built-in IMU) - Swerve Modules: Each containing: - Drive motor (e.g., NEO, Falcon500, Kraken) - Angle/steering motor (e.g., NEO 550, TalonFXS) - Absolute encoder (e.g., CANCoder, Canandmag, Thrifty Encoder) - CAN Bus: For communication (required for most modern FRC hardware)
Pre-Configuration Checklist#
Before configuring YAGSL, gather these details about your robot:
- IMU Type and ID: What gyroscope are you using and its CAN ID?
- Module Configuration: For each swerve module:
- Drive motor type, CAN ID, and gearing
- Angle motor type, CAN ID, and gearing
- Encoder type, CAN ID, and mounting offset
- Physical location relative to robot center (X, Y coordinates in inches)
- Physical Properties:
- Wheel diameter
- Drive gear ratio (motor rotations per wheel rotation)
- Angle gear ratio (motor rotations per 360° module rotation)
- Robot track width and wheelbase
- Maximum speed (feet per second)
- CAN Bus Configuration: Ensure all devices have unique IDs and proper termination
For a complete list, see Getting to Know Your Robot.
4. Configuration Steps (JSON Files, Module Setup)#
YAGSL uses JSON configuration files to define your robot's swerve drive. These files are placed in the deploy/swerve/ directory of your robot project.
Directory Structure#
deploy/
└── swerve/
├── controllerproperties.json
├── modules/
│ ├── frontleft.json
│ ├── frontright.json
│ ├── backleft.json
│ └── backright.json
├── physicalproperties.json
├── pidfproperties.json
└── swervedrive.json
Configuration Files Overview#
swervedrive.json - Global Drive Configuration#
This file defines the overall swerve drive configuration, including the IMU (gyroscope) settings and references to the individual module configuration files.
Key Properties
imu: Configures the gyroscope/IMU used for heading trackingtype: The type of IMU ("pigeon2", "navx", "adxrs450", etc.)id: CAN ID of the IMU devicecanbus: CAN bus name (usually "rio" for roboRIO bus)invertedIMU: Whether to invert the IMU reading (used for orientation correction)modules: Array of module configuration file names
Example - Pigeon2 IMU:
{
"imu": {
"type": "pigeon2",
"id": 13,
"canbus": "rio"
},
"invertedIMU": false,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
Example - NavX IMU:
{
"imu": {
"type": "navx",
"id": 0,
"canbus": null
},
"invertedIMU": false,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
Complete swervedrive.json Example:
{
"imu": {
"type": "pigeon2",
"id": 13,
"canbus": "canivore"
},
"invertedIMU": true,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
Module JSON Files - Individual Swerve Module Configuration#
Each swerve module (wheel) has its own configuration file defining the drive motor, angle motor, encoder, and physical location.
Key Properties
drive: Configuration for the drive (translation) motortype: Motor controller type ("sparkmax", "talonfx", "talonsrx", etc.)id: CAN ID of the motor controllercanbus: CAN bus nameangle: Configuration for the angle (steering) motorencoder: Configuration for the absolute encodertype: Encoder type ("cancoder", "analog", "thrifty", etc.)inverted: Motor inversion settingsdrive: Whether to invert drive motor directionangle: Whether to invert angle motor directionabsoluteEncoderInverted: Whether to invert encoder readingabsoluteEncoderOffset: Encoder offset in rotations (0.0 to 1.0)location: Physical location relative to robot centerfront: Distance forward from center (inches)left: Distance left from center (inches, negative for right side)
Example - SparkMax NEO with CANCoder (Front-Left):
{
"drive": {
"type": "sparkmax_neo",
"id": 4,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 3,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 9,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": -114.609,
"location": {
"front": 12,
"left": 12
}
}
Example - Front-Right Module (frontright.json):
{
"drive": {
"type": "sparkmax_neo",
"id": 2,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 1,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 10,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": -50.977,
"location": {
"front": 12,
"left": -12
}
}
Example - Back-Right Module (backright.json):
{
"drive": {
"type": "sparkmax_neo",
"id": 5,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 6,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 11,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": -18.281,
"location": {
"front": -12,
"left": -12
}
}
Example - Back-Left Module (backleft.json):
{
"drive": {
"type": "sparkmax_neo",
"id": 7,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 8,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 12,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": 6.504,
"location": {
"front": -12,
"left": 12
}
}
physicalproperties.json - Physical Robot Parameters#
This file defines the physical characteristics of your robot and swerve modules that affect calculations.
Key Properties
optimalVoltage: Battery voltage for calculations (usually 12.0V)wheelDiameter: Diameter of drive wheels in inchesdriveGearRatio: Gear ratio from motor to wheel (motor rotations per wheel rotation)angleGearRatio: Gear ratio from motor to module rotation (motor rotations per 360° module turn)
Example - 4-inch wheels with 6.75:1 drive ratio:
{
"optimalVoltage": 12.0,
"wheelDiameter": 4.0,
"driveGearRatio": 6.75,
"angleGearRatio": 12.8
}
Example - 3-inch wheels with 8.14:1 drive ratio:
{
"optimalVoltage": 12.0,
"wheelDiameter": 3.0,
"driveGearRatio": 8.14,
"angleGearRatio": 12.8
}
Complete physicalproperties.json Example:
{
"conversionFactors": {
"angle": {
"gearRatio": 12.8,
"factor": 0
},
"drive": {
"gearRatio": 8.14,
"diameter": 4,
"factor": 0
}
},
"currentLimit": {
"drive": 40,
"angle": 20
},
"rampRate": {
"drive": 0.25,
"angle": 0.25
},
"wheelGripCoefficientOfFriction": 1.19,
"optimalVoltage": 12
}
pidfproperties.json - Motor Control Tuning#
This file contains PIDF (Proportional, Integral, Derivative, Feedforward) tuning values for both drive and angle motors.
Key Properties
drive: PIDF values for drive motors (translation)p: Proportional gaini: Integral gaind: Derivative gainf: Feedforward gainiz: Integral zone (error threshold for integral accumulation)angle: PIDF values for angle motors (steering)
Example - SparkMax tuning values:
{
"drive": {
"p": 0.00023,
"i": 0.0000002,
"d": 1,
"f": 0,
"iz": 0
},
"angle": {
"p": 0.01,
"i": 0,
"d": 0,
"f": 0,
"iz": 0
}
}
Example - TalonFX tuning values:
{
"drive": {
"p": 1.0,
"i": 0.0,
"d": 0.0,
"f": 0.0,
"iz": 0.0
},
"angle": {
"p": 50.0,
"i": 0.0,
"d": 0.32,
"f": 0.0,
"iz": 0.0
}
}
Complete pidfproperties.json Example:
{
"drive": {
"p": 0.00023,
"i": 0.0000002,
"d": 1,
"f": 0,
"iz": 0
},
"angle": {
"p": 0.01,
"i": 0,
"d": 0,
"f": 0,
"iz": 0
}
}
controllerproperties.json - Advanced Control Settings#
This file configures advanced control parameters for heading correction and velocity control (usually left at defaults).
Key Properties
heading: PID values for heading correctionp: Proportional gain for heading controli: Integral gaind: Derivative gainvelocity: Velocity control PID valuesx: PID for X-axis velocity controly: PID for Y-axis velocity control
Controllerproperties.json Example:
{
"angleJoystickRadiusDeadband": 0.5,
"heading": {
"p": 0.4,
"i": 0,
"d": 0.01
}
}
Using the Configuration Tool#
YAGSL provides an online configuration generator: YAGSL Config Tool
- Input your robot's physical parameters
- Select hardware types and IDs
- Download the generated configuration files
- Place them in
src/main/deploy/swerve/
For manual configuration details, see Configuration Documentation.
5. Code Setup and Integration#
Importing YAGSL#
Add YAGSL as a vendor dependency (see section 2), then import in your code:
import static edu.wpi.first.units.Units.Meter;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
import frc.robot.Constants;
import java.io.File;
import java.util.Arrays;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;
import swervelib.SwerveController;
import swervelib.SwerveDrive;
import swervelib.SwerveDriveTest;
import swervelib.math.SwerveMath;
import swervelib.parser.SwerveControllerConfiguration;
import swervelib.parser.SwerveDriveConfiguration;
import swervelib.parser.SwerveParser;
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
Creating the SwerveDrive Object#
In your subsystem constructor, initialize the swerve drive from your JSON configuration files:
public SwerveSubsystem(File directory)
{
boolean blueAlliance = DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Blue;
Pose2d startingPose = blueAlliance ? new Pose2d(new Translation2d(Meter.of(1),
Meter.of(4)),
Rotation2d.fromDegrees(0))
: new Pose2d(new Translation2d(Meter.of(16),
Meter.of(4)),
Rotation2d.fromDegrees(180));
// Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created.
SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH;
try
{
swerveDrive = new SwerveParser(directory).createSwerveDrive(Constants.MAX_SPEED, startingPose);
// Alternative method if you don't want to supply the conversion factor via JSON files.
// swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, angleConversionFactor, driveConversionFactor);
} catch (Exception e)
{
throw new RuntimeException(e);
}
swerveDrive.setHeadingCorrection(false); // Heading correction should only be used while controlling the robot via angle.
swerveDrive.setCosineCompensator(false);//!SwerveDriveTelemetry.isSimulation); // Disables cosine compensation for simulations since it causes discrepancies not seen in real life.
swerveDrive.setAngularVelocityCompensation(true,
true,
0.1); //Correct for skew that gets worse as angular velocity increases. Start with a coefficient of 0.1.
swerveDrive.setModuleEncoderAutoSynchronize(false,
1); // Enable if you want to resynchronize your absolute encoders and motor encoders periodically when they are not moving.
// swerveDrive.pushOffsetsToEncoders(); // Set the absolute encoder to be used over the internal encoder and push the offsets onto it. Throws warning if not possible
}
Telemetry Setup#
YAGSL provides extensive telemetry for debugging. Configure verbosity before creating the SwerveDrive:
// Configure telemetry verbosity before creating SwerveDrive
SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH; // Options: NONE, LOW, HIGH
This adds NetworkTables entries under /SwerveDrive/ for monitoring module states, IMU data, and odometry.
Telemetry Levels
- NONE: No telemetry output
- LOW: Basic telemetry (odometry position)
- HIGH: Comprehensive telemetry (module states, IMU data, velocities, raw encoder readings)
For more code setup details, see Code Setup Documentation.
6. Basic Driving Code Examples#
Field-Oriented Drive Command#
Tip
Field-oriented drive means the robot moves relative to the field coordinate system, not its own orientation. Forward on the joystick always moves the robot toward the same direction on the field (e.g., toward the opponent's goal), regardless of how the robot is currently rotated. This is the most intuitive and commonly used drive mode for FRC competition robots.
/**
* Command to drive the robot using translative values and heading as angular velocity.
*
* @param translationX Translation in the X direction. Cubed for smoother controls.
* @param translationY Translation in the Y direction. Cubed for smoother controls.
* @param angularRotationX Angular velocity of the robot to set. Cubed for smoother controls.
* @return Drive command.
*/
public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX)
{
return run(() -> {
// Make the robot move
swerveDrive.drive(SwerveMath.scaleTranslation(new Translation2d(
translationX.getAsDouble() * swerveDrive.getMaximumChassisVelocity(),
translationY.getAsDouble() * swerveDrive.getMaximumChassisVelocity()), 0.8),
Math.pow(angularRotationX.getAsDouble(), 3) * swerveDrive.getMaximumChassisAngularVelocity(),
true,
false);
});
}
Input Scaling
SwerveMath.scaleTranslation()applies a scaling factor (0.8) to smooth translationMath.pow(..., 3)cubes the rotation input for smoother rotation control- Joystick values are multiplied by maximum chassis velocity to convert from [-1, 1] to actual m/s
Robot-Oriented Drive#
Tip
Robot-oriented drive means the robot moves relative to its own orientation. Forward on the joystick always moves the robot in the direction it's currently facing. This mode is useful for precise movements or when field orientation isn't important, but can be confusing for drivers during competition.
/**
* The primary method for controlling the drivebase. Takes a {@link Translation2d} and a rotation rate, and
* calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for
* the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used.
*
* @param translation {@link Translation2d} that is the commanded linear velocity of the robot, in meters per
* second. In robot-relative mode, positive x is torwards the bow (front) and positive y is
* torwards port (left). In field-relative mode, positive x is away from the alliance wall
* (field North) and positive y is torwards the left wall when looking through the driver station
* glass (field West).
* @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot
* relativity.
* @param fieldRelative Drive mode. True for field-relative, false for robot-relative.
*/
public void drive(Translation2d translation, double rotation, boolean fieldRelative)
{
swerveDrive.drive(translation,
rotation,
fieldRelative,
false); // Open loop is disabled since it shouldn't be used most of the time.
}
ChassisSpeeds Drive#
Tip
ChassisSpeeds drive accepts a WPILib ChassisSpeeds object, which represents the desired velocity of the robot chassis. This is useful when integrating with path planning libraries like PathPlanner or when you have calculated velocities from other sources. It provides the most control over robot motion.
/**
* Drive the robot given a chassis field oriented velocity.
*
* @param velocity Velocity according to the field.
*/
public void driveFieldOriented(ChassisSpeeds velocity)
{
swerveDrive.driveFieldOriented(velocity);
}
/**
* Drive the robot given a chassis field oriented velocity.
*
* @param velocity Velocity according to the field.
*/
public Command driveFieldOriented(Supplier<ChassisSpeeds> velocity)
{
return run(() -> {
swerveDrive.driveFieldOriented(velocity.get());
});
}
/**
* Drive according to the chassis robot oriented velocity.
*
* @param velocity Robot oriented {@link ChassisSpeeds}
*/
public void drive(ChassisSpeeds velocity)
{
swerveDrive.drive(velocity);
}
Joystick Integration#
Tip
SwerveInputStream chains joystick reads, deadband filtering, scaling, and alliance-relative control into a single reusable supplier of ChassisSpeeds. Pass it directly to driveFieldOriented() as the subsystem's default command. Axes are negated because standard joysticks return negative Y when pushed forward.
SwerveInputStream driveAngularVelocity = SwerveInputStream.of(drivebase.getSwerveDrive(),
() -> driverXbox.getLeftY() * -1,
() -> driverXbox.getLeftX() * -1)
.withControllerRotationAxis(driverXbox::getRightX)
.deadband(OperatorConstants.DEADBAND)
.scaleTranslation(0.8)
.allianceRelativeControl(true);
private void configureBindings()
{
Command driveFieldOrientedAnglularVelocity = drivebase.driveFieldOriented(driveAngularVelocity);
drivebase.setDefaultCommand(driveFieldOrientedAnglularVelocity);
}
Why are axes inverted?
Standard game controller joysticks return negative values when pushed forward (Y-axis inverted convention). Multiplying by -1 corrects this so that pushing forward on the joystick actually moves the robot forward.
Odometry and Pose Reset#
Tip
Odometry tracks the robot's position and orientation on the field using wheel encoders and IMU data. Pose reset is useful for correcting odometry drift, often done at the start of autonomous or when vision systems provide accurate position data.
/**
* Gets the current pose (position and rotation) of the robot, as reported by odometry.
*
* @return The robot's pose
*/
public Pose2d getPose()
{
return swerveDrive.getPose();
}
/**
* Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this
* method. However, if either gyro angle or module position is reset, this must be called in order for odometry to
* keep working.
*
* @param initialHolonomicPose The pose to set the odometry to
*/
public void resetOdometry(Pose2d initialHolonomicPose)
{
swerveDrive.resetOdometry(initialHolonomicPose);
}
/**
* Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
*/
public void zeroGyro()
{
swerveDrive.zeroGyro();
}
/**
* This will zero (calibrate) the robot to assume the current position is facing forward
* <p>
* If red alliance rotate the robot 180 after the drviebase zero command
*/
public void zeroGyroWithAlliance()
{
if (isRedAlliance())
{
zeroGyro();
//Set the pose 180 degrees
resetOdometry(new Pose2d(getPose().getTranslation(), Rotation2d.fromDegrees(180)));
} else
{
zeroGyro();
}
}
/**
* Gets the current yaw angle of the robot, as reported by the swerve pose estimator in the underlying drivebase.
* Note, this is not the raw gyro reading, this may be corrected from calls to resetOdometry().
*
* @return The yaw angle
*/
public Rotation2d getHeading()
{
return getPose().getRotation();
}
For more examples, see the YAGSL Examples Repository.
7. Tuning and Debugging#
PIDF Tuning#
YAGSL uses PIDF controllers for both drive and angle motors. Start with these values:
SparkMax-based systems:
{
"drive": {"p": 0.0020645, "i": 0, "d": 0, "f": 0, "iz": 0},
"angle": {"p": 0.01, "i": 0, "d": 0, "f": 0, "iz": 0}
}
TalonFX-based systems:
{
"drive": {"p": 1, "i": 0, "d": 0, "f": 0, "iz": 0},
"angle": {"p": 50, "i": 0, "d": 0.32, "f": 0, "iz": 0}
}
Tuning process: 1. Set P, I, D, F to 0 2. Increase P until oscillation occurs 3. Increase D to reduce jitter 4. Fine-tune as needed
For detailed tuning guides, see WPILib PID Tuning and YAGSL PIDF Tuning.
The Eight Steps for Inversion#
If your swerve drive spins out of control or has incorrect field orientation, use these systematic steps to fix inversion issues:
- Set
invertIMUtofalseinswervedrive.jsonand all drive motorinvertedtofalsein module JSONs - Set
invertIMUtotrue - Invert all drive motors (
"drive": {"inverted": true}) - Set
invertIMUtofalse - Flip module locations (swap front/back or left/right in configuration)
- Uninvert drive motors (
"drive": {"inverted": false}) - Set
invertIMUtotrue - Invert drive motors again (
"drive": {"inverted": true})
Test after each step. Most robots work after step 1, 3, or 7.
For complete details, see When to Invert and The Eight Steps.
Common Issues#
- Modules not facing correct direction: Check absolute encoder offsets
- Robot drifting in odometry: Verify IMU orientation and module locations
- Gears grinding: PID tuning issue, not inversion
- Inconsistent behavior: Ensure all modules have same hardware configuration
8. Links to Relevant Documentation#
- YAGSL Main Documentation: docs.yagsl.com
- Configuration Tool: YAGSL Config Generator
- Examples Repository: GitHub Examples
- WPILib Swerve Kinematics: Swerve Drive Kinematics
- CTRE Swerve Overview: Phoenix 6 Swerve
- REV Swerve Resources: REV Swerve Documentation
Additional Resources#
- Complete YAGSL Example Project: YAGSL-Example Repository - A complete, working FRC robot project demonstrating YAGSL implementation
- YAGSL Community: Join the BroncBotz Discord for support
- Known Configurations: YAGSL Configs Repository
- Advanced Features: Check examples for PathPlanner, PhotonVision, and SysId integration
This tutorial covers the essentials for getting started with YAGSL. For advanced features like vision integration or custom control algorithms, explore the examples and documentation further. Remember to test thoroughly on a test bench before field use!