Class SwerveModuleConstantsFactory<DriveMotorConfigsT extends ParentConfiguration,SteerMotorConfigsT extends ParentConfiguration,EncoderConfigsT extends ParentConfiguration>
SwerveModuleConstants.-
Field Summary
FieldsModifier and TypeFieldDescriptiondoubleCoupled gear ratio between the azimuth encoder and the drive motor.doubleSimulated drive voltage required to overcome friction.doubleSimulated drive inertia.The closed-loop output type to use for the drive motors.The drive motor closed-loop gains.doubleGear ratio between the drive motor and the wheel.The initial configs used to configure the drive motor of the swerve module.Choose the motor used for the drive motor.The initial configs used to configure the azimuth encoder of the swerve module.Choose how the feedback sensors should be configured.doubleThe maximum amount of stator current the drive motors can apply without slippage.doubleWhen using open-loop drive control, this specifies the speed at which the robot travels when driven with 12 volts.doubleSimulated steer voltage required to overcome friction.doubleSimulated azimuthal inertia.The closed-loop output type to use for the steer motors.The steer motor closed-loop gains.doubleGear ratio between the steer motor and the azimuth encoder.The initial configs used to configure the steer motor of the swerve module.Choose the motor used for the steer motor.doubleRadius of the driving wheel in meters. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptioncreateModuleConstants(int steerMotorId, int driveMotorId, int encoderId, double encoderOffset, double locationX, double locationY, boolean driveMotorInverted, boolean steerMotorInverted, boolean encoderInverted) Creates the constants for a swerve module with the given properties.createModuleConstants(int steerMotorId, int driveMotorId, int encoderId, Angle encoderOffset, Distance locationX, Distance locationY, boolean driveMotorInverted, boolean steerMotorInverted, boolean encoderInverted) Creates the constants for a swerve module with the given properties.withCouplingGearRatio(double newCouplingGearRatio) Modifies the CouplingGearRatio parameter and returns itself.withDriveFrictionVoltage(double newDriveFrictionVoltage) Modifies the DriveFrictionVoltage parameter and returns itself.withDriveFrictionVoltage(Voltage newDriveFrictionVoltage) Modifies the DriveFrictionVoltage parameter and returns itself.withDriveInertia(double newDriveInertia) Modifies the DriveInertia parameter and returns itself.withDriveInertia(MomentOfInertia newDriveInertia) Modifies the DriveInertia parameter and returns itself.withDriveMotorClosedLoopOutput(SwerveModuleConstants.ClosedLoopOutputType newDriveMotorClosedLoopOutput) Modifies the DriveMotorClosedLoopOutput parameter and returns itself.withDriveMotorGains(Slot0Configs newDriveMotorGains) Modifies the DriveMotorGains parameter and returns itself.withDriveMotorGearRatio(double newDriveMotorGearRatio) Modifies the DriveMotorGearRatio parameter and returns itself.withDriveMotorInitialConfigs(DriveMotorConfigsT newDriveMotorInitialConfigs) Modifies the DriveMotorInitialConfigs parameter and returns itself.withDriveMotorType(SwerveModuleConstants.DriveMotorArrangement newDriveMotorType) Modifies the DriveMotorType parameter and returns itself.withEncoderInitialConfigs(EncoderConfigsT newEncoderInitialConfigs) Modifies the EncoderInitialConfigs parameter and returns itself.withFeedbackSource(SwerveModuleConstants.SteerFeedbackType newFeedbackSource) Modifies the FeedbackSource parameter and returns itself.withSlipCurrent(double newSlipCurrent) Modifies the SlipCurrent parameter and returns itself.withSlipCurrent(Current newSlipCurrent) Modifies the SlipCurrent parameter and returns itself.withSpeedAt12Volts(double newSpeedAt12Volts) Modifies the SpeedAt12Volts parameter and returns itself.withSpeedAt12Volts(LinearVelocity newSpeedAt12Volts) Modifies the SpeedAt12Volts parameter and returns itself.withSteerFrictionVoltage(double newSteerFrictionVoltage) Modifies the SteerFrictionVoltage parameter and returns itself.withSteerFrictionVoltage(Voltage newSteerFrictionVoltage) Modifies the SteerFrictionVoltage parameter and returns itself.withSteerInertia(double newSteerInertia) Modifies the SteerInertia parameter and returns itself.withSteerInertia(MomentOfInertia newSteerInertia) Modifies the SteerInertia parameter and returns itself.withSteerMotorClosedLoopOutput(SwerveModuleConstants.ClosedLoopOutputType newSteerMotorClosedLoopOutput) Modifies the SteerMotorClosedLoopOutput parameter and returns itself.withSteerMotorGains(Slot0Configs newSteerMotorGains) Modifies the SteerMotorGains parameter and returns itself.withSteerMotorGearRatio(double newSteerMotorGearRatio) Modifies the SteerMotorGearRatio parameter and returns itself.withSteerMotorInitialConfigs(SteerMotorConfigsT newSteerMotorInitialConfigs) Modifies the SteerMotorInitialConfigs parameter and returns itself.withSteerMotorType(SwerveModuleConstants.SteerMotorArrangement newSteerMotorType) Modifies the SteerMotorType parameter and returns itself.withWheelRadius(double newWheelRadius) Modifies the WheelRadius parameter and returns itself.withWheelRadius(Distance newWheelRadius) Modifies the WheelRadius parameter and returns itself.
-
Field Details
-
DriveMotorGearRatio
Gear ratio between the drive motor and the wheel. -
SteerMotorGearRatio
Gear ratio between the steer motor and the azimuth encoder. For example, the SDS Mk4 has a steering ratio of 12.8. -
CouplingGearRatio
Coupled gear ratio between the azimuth encoder and the drive motor.For a typical swerve module, the azimuth turn motor also drives the wheel a nontrivial amount, which affects the accuracy of odometry and control. This ratio represents the number of rotations of the drive motor caused by a rotation of the azimuth.
-
WheelRadius
Radius of the driving wheel in meters. -
SteerMotorGains
The steer motor closed-loop gains.The steer motor uses the control ouput type specified by
SteerMotorClosedLoopOutputand anySwerveModule.SteerRequestType. These gains operate on azimuth rotations (after the gear ratio). -
DriveMotorGains
The drive motor closed-loop gains.When using closed-loop control, the drive motor uses the control output type specified by
DriveMotorClosedLoopOutputand any closed-loopSwerveModule.DriveRequestType. These gains operate on motor rotor rotations (before the gear ratio). -
SteerMotorClosedLoopOutput
The closed-loop output type to use for the steer motors. -
DriveMotorClosedLoopOutput
The closed-loop output type to use for the drive motors. -
SlipCurrent
The maximum amount of stator current the drive motors can apply without slippage. -
SpeedAt12Volts
When using open-loop drive control, this specifies the speed at which the robot travels when driven with 12 volts. This is used to approximate the output for a desired velocity. If using closed loop control, this value is ignored. -
DriveMotorType
Choose the motor used for the drive motor.If using a Talon FX, this should be set to TalonFX_Integrated. If using a Talon FXS, this should be set to the motor attached to the Talon FXS.
-
SteerMotorType
Choose the motor used for the steer motor.If using a Talon FX, this should be set to TalonFX_Integrated. If using a Talon FXS, this should be set to the motor attached to the Talon FXS.
-
FeedbackSource
Choose how the feedback sensors should be configured.If the robot does not support Pro, then this should be set to RemoteCANcoder. Otherwise, users have the option to use either FusedCANcoder or SyncCANcoder depending on if there is a risk that the CANcoder can fail in a way to provide "good" data.
If this is set to FusedCANcoder or SyncCANcoder when the steer motor is not Pro-licensed, the device will automatically fall back to RemoteCANcoder and report a UsingProFeatureOnUnlicensedDevice status code.
-
DriveMotorInitialConfigs
The initial configs used to configure the drive motor of the swerve module. The default value is the factory-default.Users may change the initial configuration as they need. Any config that's not referenced in the
SwerveModuleConstantsclass is available to be changed.The list of configs that will be overwritten is as follows:
-
MotorOutputConfigs.NeutralMode(Brake mode, overwritten withSwerveDrivetrain.configNeutralMode(com.ctre.phoenix6.signals.NeutralModeValue)) -
MotorOutputConfigs.Inverted(SwerveModuleConstants.DriveMotorInverted) -
Slot0Configs(SwerveModuleConstants.DriveMotorGains) -
CurrentLimitsConfigs.StatorCurrentLimit/TorqueCurrentConfigs.PeakForwardTorqueCurrent/TorqueCurrentConfigs.PeakReverseTorqueCurrent(SwerveModuleConstants.SlipCurrent) -
CurrentLimitsConfigs.StatorCurrentLimitEnable(Enabled)
-
-
SteerMotorInitialConfigs
The initial configs used to configure the steer motor of the swerve module. The default value is the factory-default.Users may change the initial configuration as they need. Any config that's not referenced in the
SwerveModuleConstantsclass is available to be changed.The list of configs that will be overwritten is as follows:
-
MotorOutputConfigs.NeutralMode(Brake mode) -
MotorOutputConfigs.Inverted(SwerveModuleConstants.SteerMotorInverted) -
Slot0Configs(SwerveModuleConstants.SteerMotorGains) -
FeedbackConfigs.FeedbackRemoteSensorID(SwerveModuleConstants.EncoderId) -
FeedbackConfigs.FeedbackSensorSource(SwerveModuleConstants.FeedbackSource) -
FeedbackConfigs.RotorToSensorRatio(SwerveModuleConstants.SteerMotorGearRatio) -
MotionMagicConfigs.MotionMagicExpo_kV/MotionMagicConfigs.MotionMagicExpo_kA(Calculated from gear ratios) -
ClosedLoopGeneralConfigs.ContinuousWrap(true)
-
-
EncoderInitialConfigs
The initial configs used to configure the azimuth encoder of the swerve module. The default value is the factory-default.Users may change the initial configuration as they need. Any config that's not referenced in the
SwerveModuleConstantsclass is available to be changed.For CANcoder, the list of configs that will be overwritten is as follows:
-
SteerInertia
Simulated azimuthal inertia. -
DriveInertia
Simulated drive inertia. -
SteerFrictionVoltage
Simulated steer voltage required to overcome friction. -
DriveFrictionVoltage
Simulated drive voltage required to overcome friction.
-
-
Constructor Details
-
SwerveModuleConstantsFactory
public SwerveModuleConstantsFactory()
-
-
Method Details
-
withDriveMotorGearRatio
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveMotorGearRatioEncoderConfigsT> (double newDriveMotorGearRatio) Modifies the DriveMotorGearRatio parameter and returns itself.Gear ratio between the drive motor and the wheel.
- Parameters:
newDriveMotorGearRatio- Parameter to modify- Returns:
- this object
-
withSteerMotorGearRatio
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerMotorGearRatioEncoderConfigsT> (double newSteerMotorGearRatio) Modifies the SteerMotorGearRatio parameter and returns itself.Gear ratio between the steer motor and the azimuth encoder. For example, the SDS Mk4 has a steering ratio of 12.8.
- Parameters:
newSteerMotorGearRatio- Parameter to modify- Returns:
- this object
-
withCouplingGearRatio
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withCouplingGearRatioEncoderConfigsT> (double newCouplingGearRatio) Modifies the CouplingGearRatio parameter and returns itself.Coupled gear ratio between the azimuth encoder and the drive motor.
For a typical swerve module, the azimuth turn motor also drives the wheel a nontrivial amount, which affects the accuracy of odometry and control. This ratio represents the number of rotations of the drive motor caused by a rotation of the azimuth.
- Parameters:
newCouplingGearRatio- Parameter to modify- Returns:
- this object
-
withWheelRadius
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withWheelRadiusEncoderConfigsT> (double newWheelRadius) Modifies the WheelRadius parameter and returns itself.Radius of the driving wheel in meters.
- Parameters:
newWheelRadius- Parameter to modify- Returns:
- this object
-
withWheelRadius
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withWheelRadiusEncoderConfigsT> (Distance newWheelRadius) Modifies the WheelRadius parameter and returns itself.Radius of the driving wheel in meters.
- Parameters:
newWheelRadius- Parameter to modify- Returns:
- this object
-
withSteerMotorGains
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerMotorGainsEncoderConfigsT> (Slot0Configs newSteerMotorGains) Modifies the SteerMotorGains parameter and returns itself.The steer motor closed-loop gains.
The steer motor uses the control ouput type specified by
SteerMotorClosedLoopOutputand anySwerveModule.SteerRequestType. These gains operate on azimuth rotations (after the gear ratio).- Parameters:
newSteerMotorGains- Parameter to modify- Returns:
- this object
-
withDriveMotorGains
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveMotorGainsEncoderConfigsT> (Slot0Configs newDriveMotorGains) Modifies the DriveMotorGains parameter and returns itself.The drive motor closed-loop gains.
When using closed-loop control, the drive motor uses the control output type specified by
DriveMotorClosedLoopOutputand any closed-loopSwerveModule.DriveRequestType. These gains operate on motor rotor rotations (before the gear ratio).- Parameters:
newDriveMotorGains- Parameter to modify- Returns:
- this object
-
withSteerMotorClosedLoopOutput
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerMotorClosedLoopOutputEncoderConfigsT> (SwerveModuleConstants.ClosedLoopOutputType newSteerMotorClosedLoopOutput) Modifies the SteerMotorClosedLoopOutput parameter and returns itself.The closed-loop output type to use for the steer motors.
- Parameters:
newSteerMotorClosedLoopOutput- Parameter to modify- Returns:
- this object
-
withDriveMotorClosedLoopOutput
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveMotorClosedLoopOutputEncoderConfigsT> (SwerveModuleConstants.ClosedLoopOutputType newDriveMotorClosedLoopOutput) Modifies the DriveMotorClosedLoopOutput parameter and returns itself.The closed-loop output type to use for the drive motors.
- Parameters:
newDriveMotorClosedLoopOutput- Parameter to modify- Returns:
- this object
-
withSlipCurrent
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSlipCurrentEncoderConfigsT> (double newSlipCurrent) Modifies the SlipCurrent parameter and returns itself.The maximum amount of stator current the drive motors can apply without slippage.
- Parameters:
newSlipCurrent- Parameter to modify- Returns:
- this object
-
withSlipCurrent
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSlipCurrentEncoderConfigsT> (Current newSlipCurrent) Modifies the SlipCurrent parameter and returns itself.The maximum amount of stator current the drive motors can apply without slippage.
- Parameters:
newSlipCurrent- Parameter to modify- Returns:
- this object
-
withSpeedAt12Volts
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSpeedAt12VoltsEncoderConfigsT> (double newSpeedAt12Volts) Modifies the SpeedAt12Volts parameter and returns itself.When using open-loop drive control, this specifies the speed at which the robot travels when driven with 12 volts. This is used to approximate the output for a desired velocity. If using closed loop control, this value is ignored.
- Parameters:
newSpeedAt12Volts- Parameter to modify- Returns:
- this object
-
withSpeedAt12Volts
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSpeedAt12VoltsEncoderConfigsT> (LinearVelocity newSpeedAt12Volts) Modifies the SpeedAt12Volts parameter and returns itself.When using open-loop drive control, this specifies the speed at which the robot travels when driven with 12 volts. This is used to approximate the output for a desired velocity. If using closed loop control, this value is ignored.
- Parameters:
newSpeedAt12Volts- Parameter to modify- Returns:
- this object
-
withDriveMotorType
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveMotorTypeEncoderConfigsT> (SwerveModuleConstants.DriveMotorArrangement newDriveMotorType) Modifies the DriveMotorType parameter and returns itself.Choose the motor used for the drive motor.
If using a Talon FX, this should be set to TalonFX_Integrated. If using a Talon FXS, this should be set to the motor attached to the Talon FXS.
- Parameters:
newDriveMotorType- Parameter to modify- Returns:
- this object
-
withSteerMotorType
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerMotorTypeEncoderConfigsT> (SwerveModuleConstants.SteerMotorArrangement newSteerMotorType) Modifies the SteerMotorType parameter and returns itself.Choose the motor used for the steer motor.
If using a Talon FX, this should be set to TalonFX_Integrated. If using a Talon FXS, this should be set to the motor attached to the Talon FXS.
- Parameters:
newSteerMotorType- Parameter to modify- Returns:
- this object
-
withFeedbackSource
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withFeedbackSourceEncoderConfigsT> (SwerveModuleConstants.SteerFeedbackType newFeedbackSource) Modifies the FeedbackSource parameter and returns itself.Choose how the feedback sensors should be configured.
If the robot does not support Pro, then this should be set to RemoteCANcoder. Otherwise, users have the option to use either FusedCANcoder or SyncCANcoder depending on if there is a risk that the CANcoder can fail in a way to provide "good" data.
If this is set to FusedCANcoder or SyncCANcoder when the steer motor is not Pro-licensed, the device will automatically fall back to RemoteCANcoder and report a UsingProFeatureOnUnlicensedDevice status code.
- Parameters:
newFeedbackSource- Parameter to modify- Returns:
- this object
-
withDriveMotorInitialConfigs
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveMotorInitialConfigsEncoderConfigsT> (DriveMotorConfigsT newDriveMotorInitialConfigs) Modifies the DriveMotorInitialConfigs parameter and returns itself.The initial configs used to configure the drive motor of the swerve module. The default value is the factory-default.
Users may change the initial configuration as they need. Any config that's not referenced in the
SwerveModuleConstantsclass is available to be changed.The list of configs that will be overwritten is as follows:
-
MotorOutputConfigs.NeutralMode(Brake mode, overwritten withSwerveDrivetrain.configNeutralMode(com.ctre.phoenix6.signals.NeutralModeValue)) -
MotorOutputConfigs.Inverted(SwerveModuleConstants.DriveMotorInverted) -
Slot0Configs(SwerveModuleConstants.DriveMotorGains) -
CurrentLimitsConfigs.StatorCurrentLimit/TorqueCurrentConfigs.PeakForwardTorqueCurrent/TorqueCurrentConfigs.PeakReverseTorqueCurrent(SwerveModuleConstants.SlipCurrent) -
CurrentLimitsConfigs.StatorCurrentLimitEnable(Enabled)
- Parameters:
newDriveMotorInitialConfigs- Parameter to modify- Returns:
- this object
-
-
withSteerMotorInitialConfigs
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerMotorInitialConfigsEncoderConfigsT> (SteerMotorConfigsT newSteerMotorInitialConfigs) Modifies the SteerMotorInitialConfigs parameter and returns itself.The initial configs used to configure the steer motor of the swerve module. The default value is the factory-default.
Users may change the initial configuration as they need. Any config that's not referenced in the
SwerveModuleConstantsclass is available to be changed.The list of configs that will be overwritten is as follows:
-
MotorOutputConfigs.NeutralMode(Brake mode) -
MotorOutputConfigs.Inverted(SwerveModuleConstants.SteerMotorInverted) -
Slot0Configs(SwerveModuleConstants.SteerMotorGains) -
FeedbackConfigs.FeedbackRemoteSensorID(SwerveModuleConstants.EncoderId) -
FeedbackConfigs.FeedbackSensorSource(SwerveModuleConstants.FeedbackSource) -
FeedbackConfigs.RotorToSensorRatio(SwerveModuleConstants.SteerMotorGearRatio) -
MotionMagicConfigs.MotionMagicExpo_kV/MotionMagicConfigs.MotionMagicExpo_kA(Calculated from gear ratios) -
ClosedLoopGeneralConfigs.ContinuousWrap(true)
- Parameters:
newSteerMotorInitialConfigs- Parameter to modify- Returns:
- this object
-
-
withEncoderInitialConfigs
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withEncoderInitialConfigsEncoderConfigsT> (EncoderConfigsT newEncoderInitialConfigs) Modifies the EncoderInitialConfigs parameter and returns itself.The initial configs used to configure the azimuth encoder of the swerve module. The default value is the factory-default.
Users may change the initial configuration as they need. Any config that's not referenced in the
SwerveModuleConstantsclass is available to be changed.For CANcoder, the list of configs that will be overwritten is as follows:
- Parameters:
newEncoderInitialConfigs- Parameter to modify- Returns:
- this object
-
withSteerInertia
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerInertiaEncoderConfigsT> (double newSteerInertia) Modifies the SteerInertia parameter and returns itself.Simulated azimuthal inertia.
- Parameters:
newSteerInertia- Parameter to modify- Returns:
- this object
-
withSteerInertia
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerInertiaEncoderConfigsT> (MomentOfInertia newSteerInertia) Modifies the SteerInertia parameter and returns itself.Simulated azimuthal inertia.
- Parameters:
newSteerInertia- Parameter to modify- Returns:
- this object
-
withDriveInertia
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveInertiaEncoderConfigsT> (double newDriveInertia) Modifies the DriveInertia parameter and returns itself.Simulated drive inertia.
- Parameters:
newDriveInertia- Parameter to modify- Returns:
- this object
-
withDriveInertia
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveInertiaEncoderConfigsT> (MomentOfInertia newDriveInertia) Modifies the DriveInertia parameter and returns itself.Simulated drive inertia.
- Parameters:
newDriveInertia- Parameter to modify- Returns:
- this object
-
withSteerFrictionVoltage
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerFrictionVoltageEncoderConfigsT> (double newSteerFrictionVoltage) Modifies the SteerFrictionVoltage parameter and returns itself.Simulated steer voltage required to overcome friction.
- Parameters:
newSteerFrictionVoltage- Parameter to modify- Returns:
- this object
-
withSteerFrictionVoltage
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withSteerFrictionVoltageEncoderConfigsT> (Voltage newSteerFrictionVoltage) Modifies the SteerFrictionVoltage parameter and returns itself.Simulated steer voltage required to overcome friction.
- Parameters:
newSteerFrictionVoltage- Parameter to modify- Returns:
- this object
-
withDriveFrictionVoltage
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveFrictionVoltageEncoderConfigsT> (double newDriveFrictionVoltage) Modifies the DriveFrictionVoltage parameter and returns itself.Simulated drive voltage required to overcome friction.
- Parameters:
newDriveFrictionVoltage- Parameter to modify- Returns:
- this object
-
withDriveFrictionVoltage
public SwerveModuleConstantsFactory<DriveMotorConfigsT,SteerMotorConfigsT, withDriveFrictionVoltageEncoderConfigsT> (Voltage newDriveFrictionVoltage) Modifies the DriveFrictionVoltage parameter and returns itself.Simulated drive voltage required to overcome friction.
- Parameters:
newDriveFrictionVoltage- Parameter to modify- Returns:
- this object
-
createModuleConstants
public SwerveModuleConstants<DriveMotorConfigsT,SteerMotorConfigsT, createModuleConstantsEncoderConfigsT> (int steerMotorId, int driveMotorId, int encoderId, double encoderOffset, double locationX, double locationY, boolean driveMotorInverted, boolean steerMotorInverted, boolean encoderInverted) Creates the constants for a swerve module with the given properties.- Parameters:
steerMotorId- CAN ID of the steer motor.driveMotorId- CAN ID of the drive motor.encoderId- CAN ID of the absolute encoder used for azimuth.encoderOffset- Offset of the azimuth encoder.locationX- The location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot.locationY- The location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot.driveMotorInverted- True if the drive motor is inverted.steerMotorInverted- True if the steer motor is inverted from the azimuth. The azimuth should rotate counter-clockwise (as seen from the top of the robot) for a positive motor output.encoderInverted- True if the azimuth encoder is inverted from the azimuth. The encoder should report a positive velocity when the azimuth rotates counter-clockwise (as seen from the top of the robot).- Returns:
- Constants for the swerve module
-
createModuleConstants
public SwerveModuleConstants<DriveMotorConfigsT,SteerMotorConfigsT, createModuleConstantsEncoderConfigsT> (int steerMotorId, int driveMotorId, int encoderId, Angle encoderOffset, Distance locationX, Distance locationY, boolean driveMotorInverted, boolean steerMotorInverted, boolean encoderInverted) Creates the constants for a swerve module with the given properties.- Parameters:
steerMotorId- CAN ID of the steer motor.driveMotorId- CAN ID of the drive motor.encoderId- CAN ID of the absolute encoder used for azimuth.encoderOffset- Offset of the azimuth encoder.locationX- The location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot.locationY- The location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot.driveMotorInverted- True if the drive motor is inverted.steerMotorInverted- True if the steer motor is inverted from the azimuth. The azimuth should rotate counter-clockwise (as seen from the top of the robot) for a positive motor output.encoderInverted- True if the azimuth encoder is inverted from the azimuth. The encoder should report a positive velocity when the azimuth rotates counter-clockwise (as seen from the top of the robot).- Returns:
- Constants for the swerve module
-