CTRE Phoenix 6 C++ 25.0.0-beta-4
|
All constants for a swerve module. More...
#include <ctre/phoenix6/swerve/SwerveModuleConstants.hpp>
Public Member Functions | |
constexpr | SwerveModuleConstants ()=default |
constexpr SwerveModuleConstants & | WithSteerMotorId (int newSteerMotorId) |
Modifies the SteerMotorId parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveMotorId (int newDriveMotorId) |
Modifies the DriveMotorId parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithCANcoderId (int newCANcoderId) |
Modifies the CANcoderId parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithCANcoderOffset (units::angle::turn_t newCANcoderOffset) |
Modifies the CANcoderOffset parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithLocationX (units::length::meter_t newLocationX) |
Modifies the LocationX parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithLocationY (units::length::meter_t newLocationY) |
Modifies the LocationY parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveMotorInverted (bool newDriveMotorInverted) |
Modifies the DriveMotorInverted parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerMotorInverted (bool newSteerMotorInverted) |
Modifies the SteerMotorInverted parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithCANcoderInverted (bool newCANcoderInverted) |
Modifies the CANcoderInverted parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveMotorGearRatio (units::dimensionless::scalar_t newDriveMotorGearRatio) |
Modifies the DriveMotorGearRatio parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerMotorGearRatio (units::dimensionless::scalar_t newSteerMotorGearRatio) |
Modifies the SteerMotorGearRatio parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithCouplingGearRatio (units::dimensionless::scalar_t newCouplingGearRatio) |
Modifies the CouplingGearRatio parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithWheelRadius (units::length::meter_t newWheelRadius) |
Modifies the WheelRadius parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerMotorGains (const configs::Slot0Configs &newSteerMotorGains) |
Modifies the SteerMotorGains parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveMotorGains (const configs::Slot0Configs &newDriveMotorGains) |
Modifies the DriveMotorGains parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerMotorClosedLoopOutput (ClosedLoopOutputType newSteerMotorClosedLoopOutput) |
Modifies the SteerMotorClosedLoopOutput parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveMotorClosedLoopOutput (ClosedLoopOutputType newDriveMotorClosedLoopOutput) |
Modifies the DriveMotorClosedLoopOutput parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSlipCurrent (units::current::ampere_t newSlipCurrent) |
Modifies the SlipCurrent parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSpeedAt12Volts (units::velocity::meters_per_second_t newSpeedAt12Volts) |
Modifies the SpeedAt12Volts parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithFeedbackSource (SteerFeedbackType newFeedbackSource) |
Modifies the FeedbackSource parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveMotorInitialConfigs (const configs::TalonFXConfiguration &newDriveMotorInitialConfigs) |
Modifies the DriveMotorInitialConfigs parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerMotorInitialConfigs (const configs::TalonFXConfiguration &newSteerMotorInitialConfigs) |
Modifies the SteerMotorInitialConfigs parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithCANcoderInitialConfigs (const configs::CANcoderConfiguration &newCANcoderInitialConfigs) |
Modifies the CANcoderInitialConfigs parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerInertia (units::moment_of_inertia::kilogram_square_meter_t newSteerInertia) |
Modifies the SteerInertia parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveInertia (units::moment_of_inertia::kilogram_square_meter_t newDriveInertia) |
Modifies the DriveInertia parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithSteerFrictionVoltage (units::voltage::volt_t newSteerFrictionVoltage) |
Modifies the SteerFrictionVoltage parameter and returns itself. | |
constexpr SwerveModuleConstants & | WithDriveFrictionVoltage (units::voltage::volt_t newDriveFrictionVoltage) |
Modifies the DriveFrictionVoltage parameter and returns itself. | |
Public Attributes | |
int | SteerMotorId = 0 |
CAN ID of the steer motor. | |
int | DriveMotorId = 0 |
CAN ID of the drive motor. | |
int | CANcoderId = 0 |
CAN ID of the CANcoder used for azimuth. | |
units::angle::turn_t | CANcoderOffset = 0_tr |
Offset of the CANcoder. | |
units::length::meter_t | LocationX = 0_m |
The location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot. | |
units::length::meter_t | LocationY = 0_m |
The location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot. | |
bool | DriveMotorInverted = false |
True if the drive motor is inverted. | |
bool | SteerMotorInverted = false |
True if the steer motor is inverted from the azimuth. | |
bool | CANcoderInverted = false |
True if the CANcoder is inverted from the azimuth. | |
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 CANcoder. | |
units::dimensionless::scalar_t | CouplingGearRatio = 0 |
Coupled gear ratio between the CANcoder 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. | |
SteerFeedbackType | FeedbackSource = SteerFeedbackType::FusedCANcoder |
Choose how the feedback sensors should be configured. | |
configs::TalonFXConfiguration | DriveMotorInitialConfigs = configs::TalonFXConfiguration{} |
The initial configs used to configure the drive motor of the swerve module. | |
configs::TalonFXConfiguration | SteerMotorInitialConfigs = configs::TalonFXConfiguration{} |
The initial configs used to configure the steer motor of the swerve module. | |
configs::CANcoderConfiguration | CANcoderInitialConfigs = configs::CANcoderConfiguration{} |
The initial configs used to configure the CANcoder 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. | |
All constants for a swerve module.
|
constexprdefault |
|
inlineconstexpr |
Modifies the CANcoderId parameter and returns itself.
CAN ID of the CANcoder used for azimuth.
newCANcoderId | Parameter to modify |
|
inlineconstexpr |
Modifies the CANcoderInitialConfigs parameter and returns itself.
The initial configs used to configure the CANcoder 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:
newCANcoderInitialConfigs | Parameter to modify |
|
inlineconstexpr |
Modifies the CANcoderInverted parameter and returns itself.
True if the CANcoder is inverted from the azimuth. The CANcoder should report a positive velocity when the azimuth rotates counter-clockwise (as seen from the top of the robot).
newCANcoderInverted | Parameter to modify |
|
inlineconstexpr |
Modifies the CANcoderOffset parameter and returns itself.
Offset of the CANcoder.
newCANcoderOffset | Parameter to modify |
|
inlineconstexpr |
Modifies the CouplingGearRatio parameter and returns itself.
Coupled gear ratio between the CANcoder 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 DriveMotorId parameter and returns itself.
CAN ID of the drive motor.
newDriveMotorId | 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 DriveMotorInverted parameter and returns itself.
True if the drive motor is inverted.
newDriveMotorInverted | 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 LocationX parameter and returns itself.
The location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot.
newLocationX | Parameter to modify |
|
inlineconstexpr |
Modifies the LocationY parameter and returns itself.
The location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot.
newLocationY | 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 CANcoder. For example, the SDS Mk4 has a steering ratio of 12.8.
newSteerMotorGearRatio | Parameter to modify |
|
inlineconstexpr |
Modifies the SteerMotorId parameter and returns itself.
CAN ID of the steer motor.
newSteerMotorId | 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 SteerMotorInverted parameter and returns itself.
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.
newSteerMotorInverted | Parameter to modify |
|
inlineconstexpr |
Modifies the WheelRadius parameter and returns itself.
Radius of the driving wheel in meters.
newWheelRadius | Parameter to modify |
int ctre::phoenix6::swerve::SwerveModuleConstants::CANcoderId = 0 |
CAN ID of the CANcoder used for azimuth.
configs::CANcoderConfiguration ctre::phoenix6::swerve::SwerveModuleConstants::CANcoderInitialConfigs = configs::CANcoderConfiguration{} |
The initial configs used to configure the CANcoder 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:
bool ctre::phoenix6::swerve::SwerveModuleConstants::CANcoderInverted = false |
True if the CANcoder is inverted from the azimuth.
The CANcoder should report a positive velocity when the azimuth rotates counter-clockwise (as seen from the top of the robot).
units::angle::turn_t ctre::phoenix6::swerve::SwerveModuleConstants::CANcoderOffset = 0_tr |
Offset of the CANcoder.
units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstants::CouplingGearRatio = 0 |
Coupled gear ratio between the CANcoder 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::SwerveModuleConstants::DriveFrictionVoltage = 0.25_V |
Simulated drive voltage required to overcome friction.
units::moment_of_inertia::kilogram_square_meter_t ctre::phoenix6::swerve::SwerveModuleConstants::DriveInertia = 0.001_kg_sq_m |
Simulated drive inertia.
ClosedLoopOutputType ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorClosedLoopOutput = ClosedLoopOutputType::Voltage |
The closed-loop output type to use for the drive motors.
configs::Slot0Configs ctre::phoenix6::swerve::SwerveModuleConstants::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::SwerveModuleConstants::DriveMotorGearRatio = 0 |
Gear ratio between the drive motor and the wheel.
int ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorId = 0 |
CAN ID of the drive motor.
configs::TalonFXConfiguration ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorInitialConfigs = configs::TalonFXConfiguration{} |
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:
bool ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorInverted = false |
True if the drive motor is inverted.
SteerFeedbackType ctre::phoenix6::swerve::SwerveModuleConstants::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::length::meter_t ctre::phoenix6::swerve::SwerveModuleConstants::LocationX = 0_m |
The location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot.
units::length::meter_t ctre::phoenix6::swerve::SwerveModuleConstants::LocationY = 0_m |
The location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot.
units::current::ampere_t ctre::phoenix6::swerve::SwerveModuleConstants::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::SwerveModuleConstants::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::SwerveModuleConstants::SteerFrictionVoltage = 0.25_V |
Simulated steer voltage required to overcome friction.
units::moment_of_inertia::kilogram_square_meter_t ctre::phoenix6::swerve::SwerveModuleConstants::SteerInertia = 0.00001_kg_sq_m |
Simulated azimuthal inertia.
ClosedLoopOutputType ctre::phoenix6::swerve::SwerveModuleConstants::SteerMotorClosedLoopOutput = ClosedLoopOutputType::Voltage |
The closed-loop output type to use for the steer motors.
configs::Slot0Configs ctre::phoenix6::swerve::SwerveModuleConstants::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::SwerveModuleConstants::SteerMotorGearRatio = 0 |
Gear ratio between the steer motor and the CANcoder.
For example, the SDS Mk4 has a steering ratio of 12.8.
int ctre::phoenix6::swerve::SwerveModuleConstants::SteerMotorId = 0 |
CAN ID of the steer motor.
configs::TalonFXConfiguration ctre::phoenix6::swerve::SwerveModuleConstants::SteerMotorInitialConfigs = configs::TalonFXConfiguration{} |
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:
bool ctre::phoenix6::swerve::SwerveModuleConstants::SteerMotorInverted = false |
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.
units::length::meter_t ctre::phoenix6::swerve::SwerveModuleConstants::WheelRadius = 0_m |
Radius of the driving wheel in meters.