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). This class defines characteristics that are not module specific. Mandatory parameters include withCANBusName()
and withPigeon2Id()
.
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.
SwerveDrivetrainConstants
Example¶
private static final Voltage kSteerFrictionVoltage = Volts.of(0.2);
private static final Voltage kDriveFrictionVoltage = Volts.of(0.2);
public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
Defining Module Characteristics¶
The typical FRC drivetrain includes 4 identical modules. To simplify module creation, there exists a SwerveModuleConstantsFactory
(Java) class to simplify module creation.
Mandatory parameters for this factory are:
withDriveMotorGearRatio()
- Gearing between the drive motor output shaft and the wheel.withSteerMotorGearRatio()
- Gearing between the steer motor output shaft and the azimuth gear.withWheelRadius()
- Radius of the wheel.withSteerMotorGains()
- Instance ofSlot0Configs
, closed-loop gains for the steering motor.withDriveMotorGains()
- Instance ofSlot0Configs
, closed-loop gains for the drive motor.withSteerMotorClosedLoopOutput()
- TheClosedLoopOutputType
to use for steer motor closed-loop control requests.withDriveMotorClosedLoopOutput()
- TheClosedLoopOutputType
to use for drive motor closed-loop control requests.withSpeedAt12Volts()
- Required for open-loop control, theoretical free speed at 12v applied output.withFeedbackSource()
- Instance ofSteerFeedbackType
. TypicallyFusedCANcoder
(requires Pro) orRemoteCANcoder
.
For functional simulation, the following additional parameters must be defined.
withSteerInertia()
withDriveInertia()
For a full reference of the available functions, see the API documentation of SwerveModuleConstantsFactory
(Java).
SwerveModuleConstantsFactory
Example¶
.withPigeon2Id(kPigeonId)
.withPigeon2Configs(pigeonConfigs);
private static final SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> ConstantCreator =
new SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>()
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
.withCouplingGearRatio(kCoupleRatio)
.withWheelRadius(kWheelRadius)
.withSteerMotorGains(steerGains)
.withDriveMotorGains(driveGains)
.withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput)
.withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput)
.withSlipCurrent(kSlipCurrent)
.withSpeedAt12Volts(kSpeedAt12Volts)
.withDriveMotorType(kDriveMotorType)
.withSteerMotorType(kSteerMotorType)
.withFeedbackSource(kSteerFeedbackType)
.withDriveMotorInitialConfigs(driveInitialConfigs)
Additional Constants¶
In the previous section, several optional constants are defined. These constants are not mandatory for usable swerve, but they can greatly increase swerve controllability and accuracy.
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. This can be found by placing the robot against a solid wall and slowly increase the output voltage. As the output voltage increases, plot the drive wheel velocity and stator current. Observe when the drive wheel velocity starts to rise (wheel is slipping) and at what stator current this begins.
DriveMotorInitialConfigs
/SteerMotorInitialConfigs
/CANcoderInitialConfigs
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) can be derived, or 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.
Calling createModuleConstants()
takes the following arguments:
Steer Motor ID
Drive Motor ID
Steer Encoder ID
Steer Encoder Offset
X position
Y position
Whether the drive motor is inverted
Whether the steer motor is inverted
Whether the CANcoder is inverted
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), where forward is positive X and left is positive Y.
SwerveModuleConstants
Example¶
private static final boolean kBackRightEncoderInverted = false;
private static final Distance kBackRightXPos = Inches.of(-10);
private static final Distance kBackRightYPos = Inches.of(-10);
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontLeft =
ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset,
kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, kFrontLeftSteerMotorInverted, kFrontLeftEncoderInverted
);
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontRight =
ConstantCreator.createModuleConstants(
Building the SwerveDrivetrain
¶
Note
CommandSwerveDrivetrain
is a version created by the Tuner X Swerve Project Generator that implements Subsystem
(Java) for easy command-based integration.
SwerveDrivetrain
(Java) 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
.
kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset,
kFrontRightXPos, kFrontRightYPos, kInvertRightSide, kFrontRightSteerMotorInverted, kFrontRightEncoderInverted
);
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackLeft =
ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset,
kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, kBackLeftSteerMotorInverted, kBackLeftEncoderInverted
);
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackRight =
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¶
1 // The steer motor uses any SwerveModule.SteerRequestType control request with the
2 // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
3 private static final Slot0Configs steerGains = new Slot0Configs()
4 .withKP(100).withKI(0).withKD(0.5)
5 .withKS(0.1).withKV(1.91).withKA(0)
6 .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
7 // When using closed-loop control, the drive motor uses the control
8 // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
9 private static final Slot0Configs driveGains = new Slot0Configs()
10 .withKP(0.1).withKI(0).withKD(0)
11 .withKS(0).withKV(0.124);
12
13 // The closed-loop output type to use for the steer motors;
14 // This affects the PID/FF gains for the steer motors
15 private static final ClosedLoopOutputType kSteerClosedLoopOutput = ClosedLoopOutputType.Voltage;
16 // The closed-loop output type to use for the drive motors;
17 // This affects the PID/FF gains for the drive motors
18 private static final ClosedLoopOutputType kDriveClosedLoopOutput = ClosedLoopOutputType.Voltage;
19
20 // The type of motor used for the drive motor
21 private static final DriveMotorArrangement kDriveMotorType = DriveMotorArrangement.TalonFX_Integrated;
22 // The type of motor used for the drive motor
23 private static final SteerMotorArrangement kSteerMotorType = SteerMotorArrangement.TalonFX_Integrated;
24
25 // The remote sensor feedback type to use for the steer motors;
26 // When not Pro-licensed, FusedCANcoder/SyncCANcoder automatically fall back to RemoteCANcoder
27 private static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder;
28
29 // The stator current at which the wheels start to slip;
30 // This needs to be tuned to your individual robot
31 private static final Current kSlipCurrent = Amps.of(120.0);
32
33 // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null.
34 // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
35 private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
36 private static final TalonFXConfiguration steerInitialConfigs = new TalonFXConfiguration()
37 .withCurrentLimits(
38 new CurrentLimitsConfigs()
39 // Swerve azimuth does not require much torque output, so we can set a relatively low
40 // stator current limit to help avoid brownouts without impacting performance.
41 .withStatorCurrentLimit(Amps.of(60))
42 .withStatorCurrentLimitEnable(true)
43 );
44 private static final CANcoderConfiguration encoderInitialConfigs = new CANcoderConfiguration();
45 // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
46 private static final Pigeon2Configuration pigeonConfigs = null;
47
48 // CAN bus that the devices are located on;
49 // All swerve devices must share the same CAN bus
50 public static final CANBus kCANBus = new CANBus("canivore", "./logs/example.hoot");
51
52 // Theoretical free speed (m/s) at 12 V applied output;
53 // This needs to be tuned to your individual robot
54 public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.69);
55
56 // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
57 // This may need to be tuned to your individual robot
58 private static final double kCoupleRatio = 3.8181818181818183;
59
60 private static final double kDriveGearRatio = 7.363636363636365;
61 private static final double kSteerGearRatio = 15.42857142857143;
62 private static final Distance kWheelRadius = Inches.of(2.167);
63
64 private static final boolean kInvertLeftSide = false;
65 private static final boolean kInvertRightSide = true;
66
67 private static final int kPigeonId = 1;
68
69 // These are only used for simulation
70 private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01);
71 private static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.01);
72 // Simulated voltage necessary to overcome friction
73 private static final Voltage kSteerFrictionVoltage = Volts.of(0.2);
74 private static final Voltage kDriveFrictionVoltage = Volts.of(0.2);
75
76 public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
77 .withCANBusName(kCANBus.getName())
78 .withPigeon2Id(kPigeonId)
79 .withPigeon2Configs(pigeonConfigs);
80
81 private static final SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> ConstantCreator =
82 new SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>()
83 .withDriveMotorGearRatio(kDriveGearRatio)
84 .withSteerMotorGearRatio(kSteerGearRatio)
85 .withCouplingGearRatio(kCoupleRatio)
86 .withWheelRadius(kWheelRadius)
87 .withSteerMotorGains(steerGains)
88 .withDriveMotorGains(driveGains)
89 .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput)
90 .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput)
91 .withSlipCurrent(kSlipCurrent)
92 .withSpeedAt12Volts(kSpeedAt12Volts)
93 .withDriveMotorType(kDriveMotorType)
94 .withSteerMotorType(kSteerMotorType)
95 .withFeedbackSource(kSteerFeedbackType)
96 .withDriveMotorInitialConfigs(driveInitialConfigs)
97 .withSteerMotorInitialConfigs(steerInitialConfigs)
98 .withEncoderInitialConfigs(encoderInitialConfigs)
99 .withSteerInertia(kSteerInertia)
100 .withDriveInertia(kDriveInertia)
101 .withSteerFrictionVoltage(kSteerFrictionVoltage)
102 .withDriveFrictionVoltage(kDriveFrictionVoltage);
103
104
105 // Front Left
106 private static final int kFrontLeftDriveMotorId = 3;
107 private static final int kFrontLeftSteerMotorId = 2;
108 private static final int kFrontLeftEncoderId = 1;
109 private static final Angle kFrontLeftEncoderOffset = Rotations.of(0.15234375);
110 private static final boolean kFrontLeftSteerMotorInverted = true;
111 private static final boolean kFrontLeftEncoderInverted = false;
112
113 private static final Distance kFrontLeftXPos = Inches.of(10);
114 private static final Distance kFrontLeftYPos = Inches.of(10);
115
116 // Front Right
117 private static final int kFrontRightDriveMotorId = 1;
118 private static final int kFrontRightSteerMotorId = 0;
119 private static final int kFrontRightEncoderId = 0;
120 private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.4873046875);
121 private static final boolean kFrontRightSteerMotorInverted = true;
122 private static final boolean kFrontRightEncoderInverted = false;
123
124 private static final Distance kFrontRightXPos = Inches.of(10);
125 private static final Distance kFrontRightYPos = Inches.of(-10);
126
127 // Back Left
128 private static final int kBackLeftDriveMotorId = 7;
129 private static final int kBackLeftSteerMotorId = 6;
130 private static final int kBackLeftEncoderId = 3;
131 private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.219482421875);
132 private static final boolean kBackLeftSteerMotorInverted = true;
133 private static final boolean kBackLeftEncoderInverted = false;
134
135 private static final Distance kBackLeftXPos = Inches.of(-10);
136 private static final Distance kBackLeftYPos = Inches.of(10);
137
138 // Back Right
139 private static final int kBackRightDriveMotorId = 5;
140 private static final int kBackRightSteerMotorId = 4;
141 private static final int kBackRightEncoderId = 2;
142 private static final Angle kBackRightEncoderOffset = Rotations.of(0.17236328125);
143 private static final boolean kBackRightSteerMotorInverted = true;
144 private static final boolean kBackRightEncoderInverted = false;
145
146 private static final Distance kBackRightXPos = Inches.of(-10);
147 private static final Distance kBackRightYPos = Inches.of(-10);
148
149
150 public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontLeft =
151 ConstantCreator.createModuleConstants(
152 kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset,
153 kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, kFrontLeftSteerMotorInverted, kFrontLeftEncoderInverted
154 );
155 public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontRight =
156 ConstantCreator.createModuleConstants(
157 kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset,
158 kFrontRightXPos, kFrontRightYPos, kInvertRightSide, kFrontRightSteerMotorInverted, kFrontRightEncoderInverted
159 );
160 public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackLeft =
161 ConstantCreator.createModuleConstants(
162 kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset,
163 kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, kBackLeftSteerMotorInverted, kBackLeftEncoderInverted
164 );
165 public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackRight =