Swerve Builder API

To simplify the API surface, both builder and factory paradigms are used. Users create a SwerveDrivetrain by first defining the global drivetrain characteristics and then each module characteristics.

Note

Phoenix 6 supports the Java units library when applicable.

Defining Drivetrain Characteristics

Drivetrain, in this instance, refers to the SwerveDrivetrainConstants class (Java, C++, Python). This class defines characteristics that are not tied to the swerve modules, such as the CAN bus or Pigeon 2 device ID.

Note

All devices in the swerve drivetrain must be on the same CAN bus.

Users can optionally provide a configuration object to apply custom configs to the Pigeon 2, such as mount orientation. Leaving the configuration object null will skip applying configs to the Pigeon 2.

Defining Module Characteristics

The typical FRC drivetrain includes 4 identical modules. To simplify module creation, the SwerveModuleConstantsFactory (Java, C++, Python) class is used to set up constants common across all modules, such as the drive/steer gear ratios and the wheel radius.

Some extra steps may be required to determine some constants, described below.

CouplingGearRatio

The ratio at which the output wheel rotates when the azimuth spins. In a traditional swerve module, this is the inverse of the 1st stage of the drive motor.

To manually determine the coupling ratio, lock the drive wheel in-place, then rotate the azimuth three times. Observe the number of rotations reported by the drive motor. The coupling ratio will be \(driveRotations / 3\), or \(driveRotations / azimuthRotations\).

SlipCurrent

This is the amount of stator current the drive motors can apply without slippage. Follow the instructions in Preventing Wheel Slip to find the slip current of the drivetrain.

DriveMotorInitialConfigs/SteerMotorInitialConfigs/EncoderInitialConfigs

An initial configuration object that can be used to apply custom configs to the backing devices for each swerve module. This is useful for situations such as applying supply current limits.

Building the Swerve Module Constants

SwerveModuleConstants (Java, C++, Python) can be created from the previous SwerveModuleConstantsFactory. A typical swerve drivetrain consists of four identical modules: Front Left, Front Right, Back Left, Back Right. While these modules can be instantiated directly (only really useful if the modules have different physical characteristics), the modules can also be created by calling createModuleConstants(...) with the aforementioned factory.

Note

The X and Y position of the modules is measured from the center point of the robot along the X and Y axes, respectively. These values use the same coordinate system as Translation2d (Java, C++, Python), where forward is positive X and left is positive Y.

Building the SwerveDrivetrain

SwerveDrivetrain (Java, C++, Python) is the class that handles odometry, configuration and control of the drivetrain. The constructor for this class takes the previous SwerveDrivetrainConstants and a list of SwerveModuleConstants.

Utilization of SwerveDrivetrain consists of SwerveRequests that define the state of the drivetrain. For full details of using SwerveRequests to control your swerve, see Swerve Requests.

Full Example

Note

CommandSwerveDrivetrain is a version created by the Tuner X Swerve Project Generator that implements Subsystem (Java, C++, Python) for easy command-based integration.

  1// Generated by the 2026 Tuner X Swerve Project Generator
  2// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
  3public class TunerConstants {
  4    // Both sets of gains need to be tuned to your individual robot.
  5
  6    // The steer motor uses any SwerveModule.SteerRequestType control request with the
  7    // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
  8    private static final Slot0Configs steerGains = new Slot0Configs()
  9        .withKP(100).withKI(0).withKD(0.5)
 10        .withKS(0.1).withKV(1.91).withKA(0)
 11        .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
 12    // When using closed-loop control, the drive motor uses the control
 13    // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
 14    private static final Slot0Configs driveGains = new Slot0Configs()
 15        .withKP(0.1).withKI(0).withKD(0)
 16        .withKS(0).withKV(0.124);
 17
 18    // The closed-loop output type to use for the steer motors;
 19    // This affects the PID/FF gains for the steer motors
 20    private static final ClosedLoopOutputType kSteerClosedLoopOutput = ClosedLoopOutputType.Voltage;
 21    // The closed-loop output type to use for the drive motors;
 22    // This affects the PID/FF gains for the drive motors
 23    private static final ClosedLoopOutputType kDriveClosedLoopOutput = ClosedLoopOutputType.Voltage;
 24
 25    // The type of motor used for the drive motor
 26    private static final DriveMotorArrangement kDriveMotorType = DriveMotorArrangement.TalonFX_Integrated;
 27    // The type of motor used for the drive motor
 28    private static final SteerMotorArrangement kSteerMotorType = SteerMotorArrangement.TalonFX_Integrated;
 29
 30    // The remote sensor feedback type to use for the steer motors;
 31    // When not Pro-licensed, Fused*/Sync* automatically fall back to Remote*
 32    private static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder;
 33
 34    // The stator current at which the wheels start to slip;
 35    // This needs to be tuned to your individual robot
 36    private static final Current kSlipCurrent = Amps.of(120);
 37
 38    // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null.
 39    // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
 40    private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
 41    private static final TalonFXConfiguration steerInitialConfigs = new TalonFXConfiguration()
 42        .withCurrentLimits(
 43            new CurrentLimitsConfigs()
 44                // Swerve azimuth does not require much torque output, so we can set a relatively low
 45                // stator current limit to help avoid brownouts without impacting performance.
 46                .withStatorCurrentLimit(Amps.of(60))
 47                .withStatorCurrentLimitEnable(true)
 48        );
 49    private static final CANcoderConfiguration encoderInitialConfigs = new CANcoderConfiguration();
 50    // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
 51    private static final Pigeon2Configuration pigeonConfigs = null;
 52
 53    // CAN bus that the devices are located on;
 54    // All swerve devices must share the same CAN bus
 55    public static final CANBus kCANBus = new CANBus("canivore", "./logs/example.hoot");
 56
 57    // Theoretical free speed (m/s) at 12 V applied output;
 58    // This needs to be tuned to your individual robot
 59    public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.54);
 60
 61    // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
 62    // This may need to be tuned to your individual robot
 63    private static final double kCoupleRatio = 3.8181818181818183;
 64
 65    private static final double kDriveGearRatio = 7.363636363636365;
 66    private static final double kSteerGearRatio = 15.42857142857143;
 67    private static final Distance kWheelRadius = Inches.of(2.167);
 68
 69    private static final boolean kInvertLeftSide = false;
 70    private static final boolean kInvertRightSide = true;
 71
 72    private static final int kPigeonId = 1;
 73
 74    // These are only used for simulation
 75    private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01);
 76    private static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.01);
 77    // Simulated voltage necessary to overcome friction
 78    private static final Voltage kSteerFrictionVoltage = Volts.of(0.2);
 79    private static final Voltage kDriveFrictionVoltage = Volts.of(0.2);
 80
 81    public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
 82            .withCANBusName(kCANBus.getName())
 83            .withPigeon2Id(kPigeonId)
 84            .withPigeon2Configs(pigeonConfigs);
 85
 86    private static final SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> ConstantCreator =
 87        new SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>()
 88            .withDriveMotorGearRatio(kDriveGearRatio)
 89            .withSteerMotorGearRatio(kSteerGearRatio)
 90            .withCouplingGearRatio(kCoupleRatio)
 91            .withWheelRadius(kWheelRadius)
 92            .withSteerMotorGains(steerGains)
 93            .withDriveMotorGains(driveGains)
 94            .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput)
 95            .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput)
 96            .withSlipCurrent(kSlipCurrent)
 97            .withSpeedAt12Volts(kSpeedAt12Volts)
 98            .withDriveMotorType(kDriveMotorType)
 99            .withSteerMotorType(kSteerMotorType)
100            .withFeedbackSource(kSteerFeedbackType)
101            .withDriveMotorInitialConfigs(driveInitialConfigs)
102            .withSteerMotorInitialConfigs(steerInitialConfigs)
103            .withEncoderInitialConfigs(encoderInitialConfigs)
104            .withSteerInertia(kSteerInertia)
105            .withDriveInertia(kDriveInertia)
106            .withSteerFrictionVoltage(kSteerFrictionVoltage)
107            .withDriveFrictionVoltage(kDriveFrictionVoltage);
108
109
110    // Front Left
111    private static final int kFrontLeftDriveMotorId = 3;
112    private static final int kFrontLeftSteerMotorId = 2;
113    private static final int kFrontLeftEncoderId = 1;
114    private static final Angle kFrontLeftEncoderOffset = Rotations.of(0.15234375);
115    private static final boolean kFrontLeftSteerMotorInverted = true;
116    private static final boolean kFrontLeftEncoderInverted = false;
117
118    private static final Distance kFrontLeftXPos = Inches.of(10);
119    private static final Distance kFrontLeftYPos = Inches.of(10);
120
121    // Front Right
122    private static final int kFrontRightDriveMotorId = 1;
123    private static final int kFrontRightSteerMotorId = 0;
124    private static final int kFrontRightEncoderId = 0;
125    private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.4873046875);
126    private static final boolean kFrontRightSteerMotorInverted = true;
127    private static final boolean kFrontRightEncoderInverted = false;
128
129    private static final Distance kFrontRightXPos = Inches.of(10);
130    private static final Distance kFrontRightYPos = Inches.of(-10);
131
132    // Back Left
133    private static final int kBackLeftDriveMotorId = 7;
134    private static final int kBackLeftSteerMotorId = 6;
135    private static final int kBackLeftEncoderId = 3;
136    private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.219482421875);
137    private static final boolean kBackLeftSteerMotorInverted = true;
138    private static final boolean kBackLeftEncoderInverted = false;
139
140    private static final Distance kBackLeftXPos = Inches.of(-10);
141    private static final Distance kBackLeftYPos = Inches.of(10);
142
143    // Back Right
144    private static final int kBackRightDriveMotorId = 5;
145    private static final int kBackRightSteerMotorId = 4;
146    private static final int kBackRightEncoderId = 2;
147    private static final Angle kBackRightEncoderOffset = Rotations.of(0.17236328125);
148    private static final boolean kBackRightSteerMotorInverted = true;
149    private static final boolean kBackRightEncoderInverted = false;
150
151    private static final Distance kBackRightXPos = Inches.of(-10);
152    private static final Distance kBackRightYPos = Inches.of(-10);
153
154
155    public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontLeft =
156        ConstantCreator.createModuleConstants(
157            kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset,
158            kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, kFrontLeftSteerMotorInverted, kFrontLeftEncoderInverted
159        );
160    public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontRight =
161        ConstantCreator.createModuleConstants(
162            kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset,
163            kFrontRightXPos, kFrontRightYPos, kInvertRightSide, kFrontRightSteerMotorInverted, kFrontRightEncoderInverted
164        );
165    public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackLeft =
166        ConstantCreator.createModuleConstants(
167            kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset,
168            kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, kBackLeftSteerMotorInverted, kBackLeftEncoderInverted
169        );
170    public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackRight =
171        ConstantCreator.createModuleConstants(
172            kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset,
173            kBackRightXPos, kBackRightYPos, kInvertRightSide, kBackRightSteerMotorInverted, kBackRightEncoderInverted
174        );
175
176    /**
177     * Creates a CommandSwerveDrivetrain instance.
178     * This should only be called once in your robot program,.
179     */
180    public static CommandSwerveDrivetrain createDrivetrain() {
181        return new CommandSwerveDrivetrain(
182            DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight
183        );
184    }
185
186
187    /**
188     * Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected device types.
189     */
190    public static class TunerSwerveDrivetrain extends SwerveDrivetrain<TalonFX, TalonFX, CANcoder> {
191        /**
192         * Constructs a CTRE SwerveDrivetrain using the specified constants.
193         * <p>
194         * This constructs the underlying hardware devices, so users should not construct
195         * the devices themselves. If they need the devices, they can access them through
196         * getters in the classes.
197         *
198         * @param drivetrainConstants   Drivetrain-wide constants for the swerve drive
199         * @param modules               Constants for each specific module
200         */
201        public TunerSwerveDrivetrain(
202            SwerveDrivetrainConstants drivetrainConstants,
203            SwerveModuleConstants<?, ?, ?>... modules
204        ) {
205            super(
206                TalonFX::new, TalonFX::new, CANcoder::new,
207                drivetrainConstants, modules
208            );
209        }
210
211        /**
212         * Constructs a CTRE SwerveDrivetrain using the specified constants.
213         * <p>
214         * This constructs the underlying hardware devices, so users should not construct
215         * the devices themselves. If they need the devices, they can access them through
216         * getters in the classes.
217         *
218         * @param drivetrainConstants     Drivetrain-wide constants for the swerve drive
219         * @param odometryUpdateFrequency The frequency to run the odometry loop. If
220         *                                unspecified or set to 0 Hz, this is 250 Hz on
221         *                                CAN FD, and 100 Hz on CAN 2.0.
222         * @param modules                 Constants for each specific module
223         */
224        public TunerSwerveDrivetrain(
225            SwerveDrivetrainConstants drivetrainConstants,
226            double odometryUpdateFrequency,
227            SwerveModuleConstants<?, ?, ?>... modules
228        ) {
229            super(
230                TalonFX::new, TalonFX::new, CANcoder::new,
231                drivetrainConstants, odometryUpdateFrequency, modules
232            );
233        }
234
235        /**
236         * Constructs a CTRE SwerveDrivetrain using the specified constants.
237         * <p>
238         * This constructs the underlying hardware devices, so users should not construct
239         * the devices themselves. If they need the devices, they can access them through
240         * getters in the classes.
241         *
242         * @param drivetrainConstants       Drivetrain-wide constants for the swerve drive
243         * @param odometryUpdateFrequency   The frequency to run the odometry loop. If
244         *                                  unspecified or set to 0 Hz, this is 250 Hz on
245         *                                  CAN FD, and 100 Hz on CAN 2.0.
246         * @param odometryStandardDeviation The standard deviation for odometry calculation
247         *                                  in the form [x, y, theta]ᵀ, with units in meters
248         *                                  and radians
249         * @param visionStandardDeviation   The standard deviation for vision calculation
250         *                                  in the form [x, y, theta]ᵀ, with units in meters
251         *                                  and radians
252         * @param modules                   Constants for each specific module
253         */
254        public TunerSwerveDrivetrain(
255            SwerveDrivetrainConstants drivetrainConstants,
256            double odometryUpdateFrequency,
257            Matrix<N3, N1> odometryStandardDeviation,
258            Matrix<N3, N1> visionStandardDeviation,
259            SwerveModuleConstants<?, ?, ?>... modules
260        ) {
261            super(
262                TalonFX::new, TalonFX::new, CANcoder::new,
263                drivetrainConstants, odometryUpdateFrequency,
264                odometryStandardDeviation, visionStandardDeviation, modules
265            );
266        }
267    }
268}
  1#include "ctre/phoenix6/swerve/SwerveDrivetrain.hpp"
  2#include "ctre/phoenix6/CANcoder.hpp"
  3#include "ctre/phoenix6/TalonFX.hpp"
  4
  5using namespace ctre::phoenix6;
  6
  7namespace subsystems {
  8    /* Forward declaration */
  9    class CommandSwerveDrivetrain;
 10}
 11
 12// Generated by the 2026 Tuner X Swerve Project Generator
 13// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
 14class TunerConstants {
 15    // Both sets of gains need to be tuned to your individual robot.
 16
 17    // The steer motor uses any SwerveModule.SteerRequestType control request with the
 18    // output type specified by SwerveModuleConstants::SteerMotorClosedLoopOutput
 19    static constexpr configs::Slot0Configs steerGains = configs::Slot0Configs{}
 20        .WithKP(100).WithKI(0).WithKD(0.5)
 21        .WithKS(0.1).WithKV(1.91).WithKA(0)
 22        .WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue::UseClosedLoopSign);
 23    // When using closed-loop control, the drive motor uses the control
 24    // output type specified by SwerveModuleConstants::DriveMotorClosedLoopOutput
 25    static constexpr configs::Slot0Configs driveGains = configs::Slot0Configs{}
 26        .WithKP(0.1).WithKI(0).WithKD(0)
 27        .WithKS(0).WithKV(0.124);
 28
 29    // The closed-loop output type to use for the steer motors;
 30    // This affects the PID/FF gains for the steer motors
 31    static constexpr swerve::ClosedLoopOutputType kSteerClosedLoopOutput = swerve::ClosedLoopOutputType::Voltage;
 32    // The closed-loop output type to use for the drive motors;
 33    // This affects the PID/FF gains for the drive motors
 34    static constexpr swerve::ClosedLoopOutputType kDriveClosedLoopOutput = swerve::ClosedLoopOutputType::Voltage;
 35
 36    // The type of motor used for the drive motor
 37    static constexpr swerve::DriveMotorArrangement kDriveMotorType = swerve::DriveMotorArrangement::TalonFX_Integrated;
 38    // The type of motor used for the drive motor
 39    static constexpr swerve::SteerMotorArrangement kSteerMotorType = swerve::SteerMotorArrangement::TalonFX_Integrated;
 40
 41    // The remote sensor feedback type to use for the steer motors;
 42    // When not Pro-licensed, Fused*/Sync* automatically fall back to Remote*
 43    static constexpr swerve::SteerFeedbackType kSteerFeedbackType = swerve::SteerFeedbackType::FusedCANcoder;
 44
 45    // The stator current at which the wheels start to slip;
 46    // This needs to be tuned to your individual robot
 47    static constexpr units::ampere_t kSlipCurrent = 120_A;
 48
 49    // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null.
 50    // Some configs will be overwritten; check the `With*InitialConfigs()` API documentation.
 51    static constexpr configs::TalonFXConfiguration driveInitialConfigs{};
 52    static constexpr configs::TalonFXConfiguration steerInitialConfigs = configs::TalonFXConfiguration{}
 53        .WithCurrentLimits(
 54            configs::CurrentLimitsConfigs{}
 55                // Swerve azimuth does not require much torque output, so we can set a relatively low
 56                // stator current limit to help avoid brownouts without impacting performance.
 57                .WithStatorCurrentLimit(60_A)
 58                .WithStatorCurrentLimitEnable(true)
 59        );
 60    static constexpr configs::CANcoderConfiguration encoderInitialConfigs{};
 61    // Configs for the Pigeon 2; leave this nullopt to skip applying Pigeon 2 configs
 62    static constexpr std::optional<configs::Pigeon2Configuration> pigeonConfigs = std::nullopt;
 63
 64    static constexpr std::string_view kCANBusName = "canivore";
 65
 66public:
 67    // CAN bus that the devices are located on;
 68    // All swerve devices must share the same CAN bus
 69    static inline const CANBus kCANBus{kCANBusName, "./logs/example.hoot"};
 70
 71    // Theoretical free speed (m/s) at 12 V applied output;
 72    // This needs to be tuned to your individual robot
 73    static constexpr units::meters_per_second_t kSpeedAt12Volts = 4.54_mps;
 74
 75private:
 76    // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
 77    // This may need to be tuned to your individual robot
 78    static constexpr units::scalar_t kCoupleRatio = 3.8181818181818183;
 79
 80    static constexpr units::scalar_t kDriveGearRatio = 7.363636363636365;
 81    static constexpr units::scalar_t kSteerGearRatio = 15.42857142857143;
 82    static constexpr units::inch_t kWheelRadius = 2.167_in;
 83
 84    static constexpr bool kInvertLeftSide = false;
 85    static constexpr bool kInvertRightSide = true;
 86
 87    static constexpr int kPigeonId = 1;
 88
 89    // These are only used for simulation
 90    static constexpr units::kilogram_square_meter_t kSteerInertia = 0.01_kg_sq_m;
 91    static constexpr units::kilogram_square_meter_t kDriveInertia = 0.01_kg_sq_m;
 92    // Simulated voltage necessary to overcome friction
 93    static constexpr units::volt_t kSteerFrictionVoltage = 0.2_V;
 94    static constexpr units::volt_t kDriveFrictionVoltage = 0.2_V;
 95
 96public:
 97    static constexpr swerve::SwerveDrivetrainConstants DrivetrainConstants = swerve::SwerveDrivetrainConstants{}
 98            .WithCANBusName(kCANBusName)
 99            .WithPigeon2Id(kPigeonId)
100            .WithPigeon2Configs(pigeonConfigs);
101
102private:
103    static constexpr swerve::SwerveModuleConstantsFactory ConstantCreator =
104        swerve::SwerveModuleConstantsFactory<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration>{}
105            .WithDriveMotorGearRatio(kDriveGearRatio)
106            .WithSteerMotorGearRatio(kSteerGearRatio)
107            .WithCouplingGearRatio(kCoupleRatio)
108            .WithWheelRadius(kWheelRadius)
109            .WithSteerMotorGains(steerGains)
110            .WithDriveMotorGains(driveGains)
111            .WithSteerMotorClosedLoopOutput(kSteerClosedLoopOutput)
112            .WithDriveMotorClosedLoopOutput(kDriveClosedLoopOutput)
113            .WithSlipCurrent(kSlipCurrent)
114            .WithSpeedAt12Volts(kSpeedAt12Volts)
115            .WithDriveMotorType(kDriveMotorType)
116            .WithSteerMotorType(kSteerMotorType)
117            .WithFeedbackSource(kSteerFeedbackType)
118            .WithDriveMotorInitialConfigs(driveInitialConfigs)
119            .WithSteerMotorInitialConfigs(steerInitialConfigs)
120            .WithEncoderInitialConfigs(encoderInitialConfigs)
121            .WithSteerInertia(kSteerInertia)
122            .WithDriveInertia(kDriveInertia)
123            .WithSteerFrictionVoltage(kSteerFrictionVoltage)
124            .WithDriveFrictionVoltage(kDriveFrictionVoltage);
125
126
127    // Front Left
128    static constexpr int kFrontLeftDriveMotorId = 3;
129    static constexpr int kFrontLeftSteerMotorId = 2;
130    static constexpr int kFrontLeftEncoderId = 1;
131    static constexpr units::turn_t kFrontLeftEncoderOffset = 0.15234375_tr;
132    static constexpr bool kFrontLeftSteerMotorInverted = true;
133    static constexpr bool kFrontLeftEncoderInverted = false;
134
135    static constexpr units::inch_t kFrontLeftXPos = 10_in;
136    static constexpr units::inch_t kFrontLeftYPos = 10_in;
137
138    // Front Right
139    static constexpr int kFrontRightDriveMotorId = 1;
140    static constexpr int kFrontRightSteerMotorId = 0;
141    static constexpr int kFrontRightEncoderId = 0;
142    static constexpr units::turn_t kFrontRightEncoderOffset = -0.4873046875_tr;
143    static constexpr bool kFrontRightSteerMotorInverted = true;
144    static constexpr bool kFrontRightEncoderInverted = false;
145
146    static constexpr units::inch_t kFrontRightXPos = 10_in;
147    static constexpr units::inch_t kFrontRightYPos = -10_in;
148
149    // Back Left
150    static constexpr int kBackLeftDriveMotorId = 7;
151    static constexpr int kBackLeftSteerMotorId = 6;
152    static constexpr int kBackLeftEncoderId = 3;
153    static constexpr units::turn_t kBackLeftEncoderOffset = -0.219482421875_tr;
154    static constexpr bool kBackLeftSteerMotorInverted = true;
155    static constexpr bool kBackLeftEncoderInverted = false;
156
157    static constexpr units::inch_t kBackLeftXPos = -10_in;
158    static constexpr units::inch_t kBackLeftYPos = 10_in;
159
160    // Back Right
161    static constexpr int kBackRightDriveMotorId = 5;
162    static constexpr int kBackRightSteerMotorId = 4;
163    static constexpr int kBackRightEncoderId = 2;
164    static constexpr units::turn_t kBackRightEncoderOffset = 0.17236328125_tr;
165    static constexpr bool kBackRightSteerMotorInverted = true;
166    static constexpr bool kBackRightEncoderInverted = false;
167
168    static constexpr units::inch_t kBackRightXPos = -10_in;
169    static constexpr units::inch_t kBackRightYPos = -10_in;
170
171
172public:
173    static constexpr swerve::SwerveModuleConstants FrontLeft = ConstantCreator.CreateModuleConstants(
174            kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset,
175            kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, kFrontLeftSteerMotorInverted, kFrontLeftEncoderInverted);
176    static constexpr swerve::SwerveModuleConstants FrontRight = ConstantCreator.CreateModuleConstants(
177            kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset,
178            kFrontRightXPos, kFrontRightYPos, kInvertRightSide, kFrontRightSteerMotorInverted, kFrontRightEncoderInverted);
179    static constexpr swerve::SwerveModuleConstants BackLeft = ConstantCreator.CreateModuleConstants(
180            kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset,
181            kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, kBackLeftSteerMotorInverted, kBackLeftEncoderInverted);
182    static constexpr swerve::SwerveModuleConstants BackRight = ConstantCreator.CreateModuleConstants(
183            kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset,
184            kBackRightXPos, kBackRightYPos, kInvertRightSide, kBackRightSteerMotorInverted, kBackRightEncoderInverted);
185
186    /**
187     * Creates a CommandSwerveDrivetrain instance.
188     * This should only be called once in your robot program.
189     */
190    static subsystems::CommandSwerveDrivetrain CreateDrivetrain();
191};
192
193
194/**
195 * \brief Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected device types.
196 */
197class TunerSwerveDrivetrain : public swerve::SwerveDrivetrain<hardware::TalonFX, hardware::TalonFX, hardware::CANcoder> {
198public:
199    using SwerveModuleConstants = swerve::SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration>;
200
201    /**
202     * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
203     *
204     * This constructs the underlying hardware devices, so users should not construct
205     * the devices themselves. If they need the devices, they can access them
206     * through getters in the classes.
207     *
208     * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
209     * \param modules             Constants for each specific module
210     */
211    template <std::same_as<SwerveModuleConstants>... ModuleConstants>
212    TunerSwerveDrivetrain(swerve::SwerveDrivetrainConstants const &driveTrainConstants, ModuleConstants const &... modules) :
213        SwerveDrivetrain{driveTrainConstants, modules...}
214    {}
215
216    /**
217     * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
218     *
219     * This constructs the underlying hardware devices, so users should not construct
220     * the devices themselves. If they need the devices, they can access them
221     * through getters in the classes.
222     *
223     * \param drivetrainConstants        Drivetrain-wide constants for the swerve drive
224     * \param odometryUpdateFrequency    The frequency to run the odometry loop. If
225     *                                   unspecified or set to 0 Hz, this is 250 Hz on
226     *                                   CAN FD, and 100 Hz on CAN 2.0.
227     * \param modules                    Constants for each specific module
228     */
229    template <std::same_as<SwerveModuleConstants>... ModuleConstants>
230    TunerSwerveDrivetrain(
231        swerve::SwerveDrivetrainConstants const &driveTrainConstants,
232        units::hertz_t odometryUpdateFrequency,
233        ModuleConstants const &... modules
234    ) :
235        SwerveDrivetrain{driveTrainConstants, odometryUpdateFrequency, modules...}
236    {}
237
238    /**
239     * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
240     *
241     * This constructs the underlying hardware devices, so users should not construct
242     * the devices themselves. If they need the devices, they can access them
243     * through getters in the classes.
244     *
245     * \param drivetrainConstants        Drivetrain-wide constants for the swerve drive
246     * \param odometryUpdateFrequency    The frequency to run the odometry loop. If
247     *                                   unspecified or set to 0 Hz, this is 250 Hz on
248     *                                   CAN FD, and 100 Hz on CAN 2.0.
249     * \param odometryStandardDeviation  The standard deviation for odometry calculation
250     *                                   in the form [x, y, theta]ᵀ, with units in meters
251     *                                   and radians
252     * \param visionStandardDeviation    The standard deviation for vision calculation
253     *                                   in the form [x, y, theta]ᵀ, with units in meters
254     *                                   and radians
255     * \param modules                    Constants for each specific module
256     */
257    template <std::same_as<SwerveModuleConstants>... ModuleConstants>
258    TunerSwerveDrivetrain(
259        swerve::SwerveDrivetrainConstants const &driveTrainConstants,
260        units::hertz_t odometryUpdateFrequency,
261        std::array<double, 3> const &odometryStandardDeviation,
262        std::array<double, 3> const &visionStandardDeviation,
263        ModuleConstants const &... modules
264    ) :
265        SwerveDrivetrain{
266            driveTrainConstants, odometryUpdateFrequency,
267            odometryStandardDeviation, visionStandardDeviation, modules...
268        }
269    {}
270};
1#include "generated/TunerConstants.h"
2#include "subsystems/CommandSwerveDrivetrain.h"
3
4subsystems::CommandSwerveDrivetrain TunerConstants::CreateDrivetrain()
5{
6    return {DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight};
7}
  1    from subsystems.command_swerve_drivetrain import CommandSwerveDrivetrain
  2
  3
  4class TunerConstants:
  5    """
  6    Generated by the 2026 Tuner X Swerve Project Generator
  7    https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
  8    """
  9
 10    # Both sets of gains need to be tuned to your individual robot
 11
 12    # The steer motor uses any SwerveModule.SteerRequestType control request with the
 13    # output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
 14    _steer_gains = (
 15        configs.Slot0Configs()
 16        .with_k_p(100)
 17        .with_k_i(0)
 18        .with_k_d(0.5)
 19        .with_k_s(0.1)
 20        .with_k_v(1.91)
 21        .with_k_a(0)
 22        .with_static_feedforward_sign(
 23            signals.StaticFeedforwardSignValue.USE_CLOSED_LOOP_SIGN
 24        )
 25    )
 26    # When using closed-loop control, the drive motor uses the control
 27    # output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
 28    _drive_gains = (
 29        configs.Slot0Configs()
 30        .with_k_p(0.1)
 31        .with_k_i(0)
 32        .with_k_d(0)
 33        .with_k_s(0)
 34        .with_k_v(0.124)
 35    )
 36
 37    # The closed-loop output type to use for the steer motors;
 38    # This affects the PID/FF gains for the steer motors
 39    _steer_closed_loop_output = swerve.ClosedLoopOutputType.VOLTAGE
 40    # The closed-loop output type to use for the drive motors;
 41    # This affects the PID/FF gains for the drive motors
 42    _drive_closed_loop_output = swerve.ClosedLoopOutputType.VOLTAGE
 43
 44    # The type of motor used for the drive motor
 45    _drive_motor_type = swerve.DriveMotorArrangement.TALON_FX_INTEGRATED
 46    # The type of motor used for the drive motor
 47    _steer_motor_type = swerve.SteerMotorArrangement.TALON_FX_INTEGRATED
 48
 49    # The remote sensor feedback type to use for the steer motors;
 50    # When not Pro-licensed, Fused*/Sync* automatically fall back to Remote*
 51    _steer_feedback_type = swerve.SteerFeedbackType.FUSED_CANCODER
 52
 53    # The stator current at which the wheels start to slip;
 54    # This needs to be tuned to your individual robot
 55    _slip_current: units.ampere = 120.0
 56
 57    # Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null.
 58    # Some configs will be overwritten; check the `with_*_initial_configs()` API documentation.
 59    _drive_initial_configs = configs.TalonFXConfiguration()
 60    _steer_initial_configs = configs.TalonFXConfiguration().with_current_limits(
 61        configs.CurrentLimitsConfigs()
 62        # Swerve azimuth does not require much torque output, so we can set a relatively low
 63        # stator current limit to help avoid brownouts without impacting performance.
 64        .with_stator_current_limit(60.0)
 65        .with_stator_current_limit_enable(True)
 66    )
 67    _encoder_initial_configs = configs.CANcoderConfiguration()
 68    # Configs for the Pigeon 2; leave this None to skip applying Pigeon 2 configs
 69    _pigeon_configs: configs.Pigeon2Configuration | None = None
 70
 71    # CAN bus that the devices are located on;
 72    # All swerve devices must share the same CAN bus
 73    canbus = CANBus("canivore", "./logs/example.hoot")
 74
 75    # Theoretical free speed (m/s) at 12 V applied output;
 76    # This needs to be tuned to your individual robot
 77    speed_at_12_volts: units.meters_per_second = 4.54
 78
 79    # Every 1 rotation of the azimuth results in _couple_ratio drive motor turns;
 80    # This may need to be tuned to your individual robot
 81    _couple_ratio = 3.8181818181818183
 82
 83    _drive_gear_ratio = 7.363636363636365
 84    _steer_gear_ratio = 15.42857142857143
 85    _wheel_radius: units.meter = inchesToMeters(2.167)
 86
 87    _invert_left_side = False
 88    _invert_right_side = True
 89
 90    _pigeon_id = 1
 91
 92    # These are only used for simulation
 93    _steer_inertia: units.kilogram_square_meter = 0.01
 94    _drive_inertia: units.kilogram_square_meter = 0.01
 95    # Simulated voltage necessary to overcome friction
 96    _steer_friction_voltage: units.volt = 0.2
 97    _drive_friction_voltage: units.volt = 0.2
 98
 99    drivetrain_constants = (
100        swerve.SwerveDrivetrainConstants()
101        .with_can_bus_name(canbus.name)
102        .with_pigeon2_id(_pigeon_id)
103        .with_pigeon2_configs(_pigeon_configs)
104    )
105
106    _constants_creator: swerve.SwerveModuleConstantsFactory[
107        configs.TalonFXConfiguration,
108        configs.TalonFXConfiguration,
109        configs.CANcoderConfiguration,
110    ] = (
111        swerve.SwerveModuleConstantsFactory()
112        .with_drive_motor_gear_ratio(_drive_gear_ratio)
113        .with_steer_motor_gear_ratio(_steer_gear_ratio)
114        .with_coupling_gear_ratio(_couple_ratio)
115        .with_wheel_radius(_wheel_radius)
116        .with_steer_motor_gains(_steer_gains)
117        .with_drive_motor_gains(_drive_gains)
118        .with_steer_motor_closed_loop_output(_steer_closed_loop_output)
119        .with_drive_motor_closed_loop_output(_drive_closed_loop_output)
120        .with_slip_current(_slip_current)
121        .with_speed_at12_volts(speed_at_12_volts)
122        .with_drive_motor_type(_drive_motor_type)
123        .with_steer_motor_type(_steer_motor_type)
124        .with_feedback_source(_steer_feedback_type)
125        .with_drive_motor_initial_configs(_drive_initial_configs)
126        .with_steer_motor_initial_configs(_steer_initial_configs)
127        .with_encoder_initial_configs(_encoder_initial_configs)
128        .with_steer_inertia(_steer_inertia)
129        .with_drive_inertia(_drive_inertia)
130        .with_steer_friction_voltage(_steer_friction_voltage)
131        .with_drive_friction_voltage(_drive_friction_voltage)
132    )
133
134
135    # Front Left
136    _front_left_drive_motor_id = 3
137    _front_left_steer_motor_id = 2
138    _front_left_encoder_id = 1
139    _front_left_encoder_offset: units.rotation = 0.15234375
140    _front_left_steer_motor_inverted = True
141    _front_left_encoder_inverted = False
142
143    _front_left_x_pos: units.meter = inchesToMeters(10)
144    _front_left_y_pos: units.meter = inchesToMeters(10)
145
146    # Front Right
147    _front_right_drive_motor_id = 1
148    _front_right_steer_motor_id = 0
149    _front_right_encoder_id = 0
150    _front_right_encoder_offset: units.rotation = -0.4873046875
151    _front_right_steer_motor_inverted = True
152    _front_right_encoder_inverted = False
153
154    _front_right_x_pos: units.meter = inchesToMeters(10)
155    _front_right_y_pos: units.meter = inchesToMeters(-10)
156
157    # Back Left
158    _back_left_drive_motor_id = 7
159    _back_left_steer_motor_id = 6
160    _back_left_encoder_id = 3
161    _back_left_encoder_offset: units.rotation = -0.219482421875
162    _back_left_steer_motor_inverted = True
163    _back_left_encoder_inverted = False
164
165    _back_left_x_pos: units.meter = inchesToMeters(-10)
166    _back_left_y_pos: units.meter = inchesToMeters(10)
167
168    # Back Right
169    _back_right_drive_motor_id = 5
170    _back_right_steer_motor_id = 4
171    _back_right_encoder_id = 2
172    _back_right_encoder_offset: units.rotation = 0.17236328125
173    _back_right_steer_motor_inverted = True
174    _back_right_encoder_inverted = False
175
176    _back_right_x_pos: units.meter = inchesToMeters(-10)
177    _back_right_y_pos: units.meter = inchesToMeters(-10)
178
179
180    front_left = _constants_creator.create_module_constants(
181        _front_left_steer_motor_id,
182        _front_left_drive_motor_id,
183        _front_left_encoder_id,
184        _front_left_encoder_offset,
185        _front_left_x_pos,
186        _front_left_y_pos,
187        _invert_left_side,
188        _front_left_steer_motor_inverted,
189        _front_left_encoder_inverted,
190    )
191    front_right = _constants_creator.create_module_constants(
192        _front_right_steer_motor_id,
193        _front_right_drive_motor_id,
194        _front_right_encoder_id,
195        _front_right_encoder_offset,
196        _front_right_x_pos,
197        _front_right_y_pos,
198        _invert_right_side,
199        _front_right_steer_motor_inverted,
200        _front_right_encoder_inverted,
201    )
202    back_left = _constants_creator.create_module_constants(
203        _back_left_steer_motor_id,
204        _back_left_drive_motor_id,
205        _back_left_encoder_id,
206        _back_left_encoder_offset,
207        _back_left_x_pos,
208        _back_left_y_pos,
209        _invert_left_side,
210        _back_left_steer_motor_inverted,
211        _back_left_encoder_inverted,
212    )
213    back_right = _constants_creator.create_module_constants(
214        _back_right_steer_motor_id,
215        _back_right_drive_motor_id,
216        _back_right_encoder_id,
217        _back_right_encoder_offset,
218        _back_right_x_pos,
219        _back_right_y_pos,
220        _invert_right_side,
221        _back_right_steer_motor_inverted,
222        _back_right_encoder_inverted,
223    )
224
225    @classmethod
226    def create_drivetrain(cls) -> "CommandSwerveDrivetrain":
227        """
228        Creates a CommandSwerveDrivetrain instance.
229        This should only be called once in your robot program.
230        """
231        from subsystems.command_swerve_drivetrain import CommandSwerveDrivetrain
232
233        return CommandSwerveDrivetrain(
234            cls.drivetrain_constants,
235            [
236                cls.front_left,
237                cls.front_right,
238                cls.back_left,
239                cls.back_right,
240            ],
241        )
242
243
244class TunerSwerveDrivetrain(
245    swerve.SwerveDrivetrain[hardware.TalonFX, hardware.TalonFX, hardware.CANcoder]
246):
247    """Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected device types."""
248
249    @overload
250    def __init__(
251        self,
252        drivetrain_constants: swerve.SwerveDrivetrainConstants,
253        modules: list[swerve.SwerveModuleConstants],
254        /,
255    ) -> None:
256        """
257        Constructs a CTRE SwerveDrivetrain using the specified constants.
258
259        This constructs the underlying hardware devices, so users should not construct
260        the devices themselves. If they need the devices, they can access them through
261        getters in the classes.
262
263        :param drivetrain_constants: Drivetrain-wide constants for the swerve drive
264        :type drivetrain_constants:  swerve.SwerveDrivetrainConstants
265        :param modules:              Constants for each specific module
266        :type modules:               list[swerve.SwerveModuleConstants]
267        """
268        ...
269
270    @overload
271    def __init__(
272        self,
273        drivetrain_constants: swerve.SwerveDrivetrainConstants,
274        odometry_update_frequency: units.hertz,
275        modules: list[swerve.SwerveModuleConstants],
276        /,
277    ) -> None:
278        """
279        Constructs a CTRE SwerveDrivetrain using the specified constants.
280
281        This constructs the underlying hardware devices, so users should not construct
282        the devices themselves. If they need the devices, they can access them through
283        getters in the classes.
284
285        :param drivetrain_constants:        Drivetrain-wide constants for the swerve drive
286        :type drivetrain_constants:         swerve.SwerveDrivetrainConstants
287        :param odometry_update_frequency:   The frequency to run the odometry loop. If
288                                            unspecified or set to 0 Hz, this is 250 Hz on
289                                            CAN FD, and 100 Hz on CAN 2.0.
290        :type odometry_update_frequency:    units.hertz
291        :param modules:                     Constants for each specific module
292        :type modules:                      list[swerve.SwerveModuleConstants]
293        """
294        ...
295
296    @overload
297    def __init__(
298        self,
299        drivetrain_constants: swerve.SwerveDrivetrainConstants,
300        odometry_update_frequency: units.hertz,
301        odometry_standard_deviation: tuple[float, float, float],
302        vision_standard_deviation: tuple[float, float, float],
303        modules: list[swerve.SwerveModuleConstants],
304        /,
305    ) -> None:
306        """
307        Constructs a CTRE SwerveDrivetrain using the specified constants.
308
309        This constructs the underlying hardware devices, so users should not construct
310        the devices themselves. If they need the devices, they can access them through
311        getters in the classes.
312
313        :param drivetrain_constants:        Drivetrain-wide constants for the swerve drive
314        :type drivetrain_constants:         swerve.SwerveDrivetrainConstants
315        :param odometry_update_frequency:   The frequency to run the odometry loop. If
316                                            unspecified or set to 0 Hz, this is 250 Hz on
317                                            CAN FD, and 100 Hz on CAN 2.0.
318        :type odometry_update_frequency:    units.hertz
319        :param odometry_standard_deviation: The standard deviation for odometry calculation
320                                            in the form [x, y, theta]ᵀ, with units in meters
321                                            and radians
322        :type odometry_standard_deviation:  tuple[float, float, float]
323        :param vision_standard_deviation:   The standard deviation for vision calculation
324                                            in the form [x, y, theta]ᵀ, with units in meters
325                                            and radians
326        :type vision_standard_deviation:    tuple[float, float, float]
327        :param modules:                     Constants for each specific module
328        :type modules:                      list[swerve.SwerveModuleConstants]
329        """
330        ...
331
332    @overload
333    def __init__(
334        self,
335        drivetrain_constants: swerve.SwerveDrivetrainConstants,
336        arg0: None,
337        arg1: None,
338        arg2: None,
339        arg3: None,
340        /,
341    ) -> None: ...
342
343    def __init__(
344        self,
345        drivetrain_constants: swerve.SwerveDrivetrainConstants,
346        arg0=None,
347        arg1=None,
348        arg2=None,
349        arg3=None,
350    ):
351        swerve.SwerveDrivetrain.__init__(
352            self,
353            hardware.TalonFX,
354            hardware.TalonFX,
355            hardware.CANcoder,
356            drivetrain_constants,
357            arg0,
358            arg1,
359            arg2,
360            arg3,
361        )