CTRE Phoenix 6 C++ 25.3.1
|
Constants that are common across the swerve modules, used for creating instances of module-specific SwerveModuleConstants. More...
#include <ctre/phoenix6/swerve/SwerveModuleConstants.hpp>
Public Member Functions | |
constexpr | SwerveModuleConstantsFactory ()=default |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveMotorGearRatio (units::dimensionless::scalar_t newDriveMotorGearRatio) |
Modifies the DriveMotorGearRatio parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerMotorGearRatio (units::dimensionless::scalar_t newSteerMotorGearRatio) |
Modifies the SteerMotorGearRatio parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithCouplingGearRatio (units::dimensionless::scalar_t newCouplingGearRatio) |
Modifies the CouplingGearRatio parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithWheelRadius (units::length::meter_t newWheelRadius) |
Modifies the WheelRadius parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerMotorGains (configs::Slot0Configs newSteerMotorGains) |
Modifies the SteerMotorGains parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveMotorGains (configs::Slot0Configs newDriveMotorGains) |
Modifies the DriveMotorGains parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerMotorClosedLoopOutput (ClosedLoopOutputType newSteerMotorClosedLoopOutput) |
Modifies the SteerMotorClosedLoopOutput parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveMotorClosedLoopOutput (ClosedLoopOutputType newDriveMotorClosedLoopOutput) |
Modifies the DriveMotorClosedLoopOutput parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSlipCurrent (units::current::ampere_t newSlipCurrent) |
Modifies the SlipCurrent parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSpeedAt12Volts (units::velocity::meters_per_second_t newSpeedAt12Volts) |
Modifies the SpeedAt12Volts parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveMotorType (DriveMotorArrangement newDriveMotorType) |
Modifies the DriveMotorType parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerMotorType (SteerMotorArrangement newSteerMotorType) |
Modifies the SteerMotorType parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithFeedbackSource (SteerFeedbackType newFeedbackSource) |
Modifies the FeedbackSource parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveMotorInitialConfigs (DriveMotorConfigsT newDriveMotorInitialConfigs) |
Modifies the DriveMotorInitialConfigs parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerMotorInitialConfigs (SteerMotorConfigsT newSteerMotorInitialConfigs) |
Modifies the SteerMotorInitialConfigs parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithEncoderInitialConfigs (EncoderConfigsT newEncoderInitialConfigs) |
Modifies the EncoderInitialConfigs parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerInertia (units::moment_of_inertia::kilogram_square_meter_t newSteerInertia) |
Modifies the SteerInertia parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveInertia (units::moment_of_inertia::kilogram_square_meter_t newDriveInertia) |
Modifies the DriveInertia parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithSteerFrictionVoltage (units::voltage::volt_t newSteerFrictionVoltage) |
Modifies the SteerFrictionVoltage parameter and returns itself. | |
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & | WithDriveFrictionVoltage (units::voltage::volt_t newDriveFrictionVoltage) |
Modifies the DriveFrictionVoltage parameter and returns itself. | |
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > | CreateModuleConstants (int steerMotorId, int driveMotorId, int encoderId, units::angle::turn_t encoderOffset, units::length::meter_t locationX, units::length::meter_t locationY, bool driveMotorInverted, bool steerMotorInverted, bool encoderInverted) const |
Creates the constants for a swerve module with the given properties. | |
Public Attributes | |
units::dimensionless::scalar_t | DriveMotorGearRatio = 0 |
Gear ratio between the drive motor and the wheel. | |
units::dimensionless::scalar_t | SteerMotorGearRatio = 0 |
Gear ratio between the steer motor and the azimuth encoder. | |
units::dimensionless::scalar_t | CouplingGearRatio = 0 |
Coupled gear ratio between the azimuth encoder and the drive motor. | |
units::length::meter_t | WheelRadius = 0_m |
Radius of the driving wheel in meters. | |
configs::Slot0Configs | SteerMotorGains = configs::Slot0Configs{} |
The steer motor closed-loop gains. | |
configs::Slot0Configs | DriveMotorGains = configs::Slot0Configs{} |
The drive motor closed-loop gains. | |
ClosedLoopOutputType | SteerMotorClosedLoopOutput = ClosedLoopOutputType::Voltage |
The closed-loop output type to use for the steer motors. | |
ClosedLoopOutputType | DriveMotorClosedLoopOutput = ClosedLoopOutputType::Voltage |
The closed-loop output type to use for the drive motors. | |
units::current::ampere_t | SlipCurrent = 120_A |
The maximum amount of stator current the drive motors can apply without slippage. | |
units::velocity::meters_per_second_t | SpeedAt12Volts = 0_mps |
When using open-loop drive control, this specifies the speed at which the robot travels when driven with 12 volts. | |
DriveMotorArrangement | DriveMotorType = DriveMotorArrangement::TalonFX_Integrated |
Choose the motor used for the drive motor. | |
SteerMotorArrangement | SteerMotorType = SteerMotorArrangement::TalonFX_Integrated |
Choose the motor used for the steer motor. | |
SteerFeedbackType | FeedbackSource = SteerFeedbackType::FusedCANcoder |
Choose how the feedback sensors should be configured. | |
DriveMotorConfigsT | DriveMotorInitialConfigs = {} |
The initial configs used to configure the drive motor of the swerve module. | |
SteerMotorConfigsT | SteerMotorInitialConfigs = {} |
The initial configs used to configure the steer motor of the swerve module. | |
EncoderConfigsT | EncoderInitialConfigs = {} |
The initial configs used to configure the azimuth encoder of the swerve module. | |
units::moment_of_inertia::kilogram_square_meter_t | SteerInertia = 0.00001_kg_sq_m |
Simulated azimuthal inertia. | |
units::moment_of_inertia::kilogram_square_meter_t | DriveInertia = 0.001_kg_sq_m |
Simulated drive inertia. | |
units::voltage::volt_t | SteerFrictionVoltage = 0.25_V |
Simulated steer voltage required to overcome friction. | |
units::voltage::volt_t | DriveFrictionVoltage = 0.25_V |
Simulated drive voltage required to overcome friction. | |
Constants that are common across the swerve modules, used for creating instances of module-specific SwerveModuleConstants.
|
constexprdefault |
|
inlineconstexpr |
Creates the constants for a swerve module with the given properties.
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). |
|
inlineconstexpr |
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.
newCouplingGearRatio | Parameter to modify |
|
inlineconstexpr |
Modifies the DriveFrictionVoltage parameter and returns itself.
Simulated drive voltage required to overcome friction.
newDriveFrictionVoltage | Parameter to modify |
|
inlineconstexpr |
Modifies the DriveInertia parameter and returns itself.
Simulated drive inertia.
newDriveInertia | Parameter to modify |
|
inlineconstexpr |
Modifies the DriveMotorClosedLoopOutput parameter and returns itself.
The closed-loop output type to use for the drive motors.
newDriveMotorClosedLoopOutput | Parameter to modify |
|
inlineconstexpr |
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 DriveMotorClosedLoopOutput and any closed-loop SwerveModule#DriveRequestType. These gains operate on motor rotor rotations (before the gear ratio).
newDriveMotorGains | Parameter to modify |
|
inlineconstexpr |
Modifies the DriveMotorGearRatio parameter and returns itself.
Gear ratio between the drive motor and the wheel.
newDriveMotorGearRatio | Parameter to modify |
|
inlineconstexpr |
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 SwerveModuleConstants class is available to be changed.
The list of configs that will be overwritten is as follows:
newDriveMotorInitialConfigs | Parameter to modify |
|
inlineconstexpr |
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.
newDriveMotorType | Parameter to modify |
|
inlineconstexpr |
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 SwerveModuleConstants class is available to be changed.
For CANcoder, the list of configs that will be overwritten is as follows:
newEncoderInitialConfigs | Parameter to modify |
|
inlineconstexpr |
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.
newFeedbackSource | Parameter to modify |
|
inlineconstexpr |
Modifies the SlipCurrent parameter and returns itself.
The maximum amount of stator current the drive motors can apply without slippage.
newSlipCurrent | Parameter to modify |
|
inlineconstexpr |
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.
newSpeedAt12Volts | Parameter to modify |
|
inlineconstexpr |
Modifies the SteerFrictionVoltage parameter and returns itself.
Simulated steer voltage required to overcome friction.
newSteerFrictionVoltage | Parameter to modify |
|
inlineconstexpr |
Modifies the SteerInertia parameter and returns itself.
Simulated azimuthal inertia.
newSteerInertia | Parameter to modify |
|
inlineconstexpr |
Modifies the SteerMotorClosedLoopOutput parameter and returns itself.
The closed-loop output type to use for the steer motors.
newSteerMotorClosedLoopOutput | Parameter to modify |
|
inlineconstexpr |
Modifies the SteerMotorGains parameter and returns itself.
The steer motor closed-loop gains.
The steer motor uses the control ouput type specified by SteerMotorClosedLoopOutput and any SwerveModule#SteerRequestType. These gains operate on azimuth rotations (after the gear ratio).
newSteerMotorGains | Parameter to modify |
|
inlineconstexpr |
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.
newSteerMotorGearRatio | Parameter to modify |
|
inlineconstexpr |
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 SwerveModuleConstants class is available to be changed.
The list of configs that will be overwritten is as follows:
newSteerMotorInitialConfigs | Parameter to modify |
|
inlineconstexpr |
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.
newSteerMotorType | Parameter to modify |
|
inlineconstexpr |
Modifies the WheelRadius parameter and returns itself.
Radius of the driving wheel in meters.
newWheelRadius | Parameter to modify |
units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::CouplingGearRatio = 0 |
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.
units::voltage::volt_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::DriveFrictionVoltage = 0.25_V |
Simulated drive voltage required to overcome friction.
units::moment_of_inertia::kilogram_square_meter_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::DriveInertia = 0.001_kg_sq_m |
Simulated drive inertia.
ClosedLoopOutputType ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::DriveMotorClosedLoopOutput = ClosedLoopOutputType::Voltage |
The closed-loop output type to use for the drive motors.
configs::Slot0Configs ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::DriveMotorGains = configs::Slot0Configs{} |
The drive motor closed-loop gains.
When using closed-loop control, the drive motor uses the control output type specified by DriveMotorClosedLoopOutput and any closed-loop SwerveModule#DriveRequestType. These gains operate on motor rotor rotations (before the gear ratio).
units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::DriveMotorGearRatio = 0 |
Gear ratio between the drive motor and the wheel.
DriveMotorConfigsT ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::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 SwerveModuleConstants class is available to be changed.
The list of configs that will be overwritten is as follows:
DriveMotorArrangement ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::DriveMotorType = DriveMotorArrangement::TalonFX_Integrated |
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.
EncoderConfigsT ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::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 SwerveModuleConstants class is available to be changed.
For CANcoder, the list of configs that will be overwritten is as follows:
SteerFeedbackType ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::FeedbackSource = SteerFeedbackType::FusedCANcoder |
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.
units::current::ampere_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SlipCurrent = 120_A |
The maximum amount of stator current the drive motors can apply without slippage.
units::velocity::meters_per_second_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SpeedAt12Volts = 0_mps |
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.
units::voltage::volt_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SteerFrictionVoltage = 0.25_V |
Simulated steer voltage required to overcome friction.
units::moment_of_inertia::kilogram_square_meter_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SteerInertia = 0.00001_kg_sq_m |
Simulated azimuthal inertia.
ClosedLoopOutputType ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SteerMotorClosedLoopOutput = ClosedLoopOutputType::Voltage |
The closed-loop output type to use for the steer motors.
configs::Slot0Configs ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SteerMotorGains = configs::Slot0Configs{} |
The steer motor closed-loop gains.
The steer motor uses the control ouput type specified by SteerMotorClosedLoopOutput and any SwerveModule#SteerRequestType. These gains operate on azimuth rotations (after the gear ratio).
units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SteerMotorGearRatio = 0 |
Gear ratio between the steer motor and the azimuth encoder.
For example, the SDS Mk4 has a steering ratio of 12.8.
SteerMotorConfigsT ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::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 SwerveModuleConstants class is available to be changed.
The list of configs that will be overwritten is as follows:
SteerMotorArrangement ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::SteerMotorType = SteerMotorArrangement::TalonFX_Integrated |
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.
units::length::meter_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT, typename, typename, typename >::WheelRadius = 0_m |
Radius of the driving wheel in meters.