CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
ctre::phoenix6::swerve::SwerveModuleConstants Struct Reference

All constants for a swerve module. More...

#include <ctre/phoenix6/swerve/SwerveModuleConstants.hpp>

Public Member Functions

constexpr SwerveModuleConstants ()=default
 
constexpr SwerveModuleConstantsWithSteerMotorId (int newSteerMotorId)
 Modifies the SteerMotorId parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveMotorId (int newDriveMotorId)
 Modifies the DriveMotorId parameter and returns itself.
 
constexpr SwerveModuleConstantsWithCANcoderId (int newCANcoderId)
 Modifies the CANcoderId parameter and returns itself.
 
constexpr SwerveModuleConstantsWithCANcoderOffset (units::angle::turn_t newCANcoderOffset)
 Modifies the CANcoderOffset parameter and returns itself.
 
constexpr SwerveModuleConstantsWithLocationX (units::length::meter_t newLocationX)
 Modifies the LocationX parameter and returns itself.
 
constexpr SwerveModuleConstantsWithLocationY (units::length::meter_t newLocationY)
 Modifies the LocationY parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveMotorInverted (bool newDriveMotorInverted)
 Modifies the DriveMotorInverted parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerMotorInverted (bool newSteerMotorInverted)
 Modifies the SteerMotorInverted parameter and returns itself.
 
constexpr SwerveModuleConstantsWithCANcoderInverted (bool newCANcoderInverted)
 Modifies the CANcoderInverted parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveMotorGearRatio (units::dimensionless::scalar_t newDriveMotorGearRatio)
 Modifies the DriveMotorGearRatio parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerMotorGearRatio (units::dimensionless::scalar_t newSteerMotorGearRatio)
 Modifies the SteerMotorGearRatio parameter and returns itself.
 
constexpr SwerveModuleConstantsWithCouplingGearRatio (units::dimensionless::scalar_t newCouplingGearRatio)
 Modifies the CouplingGearRatio parameter and returns itself.
 
constexpr SwerveModuleConstantsWithWheelRadius (units::length::meter_t newWheelRadius)
 Modifies the WheelRadius parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerMotorGains (const configs::Slot0Configs &newSteerMotorGains)
 Modifies the SteerMotorGains parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveMotorGains (const configs::Slot0Configs &newDriveMotorGains)
 Modifies the DriveMotorGains parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerMotorClosedLoopOutput (ClosedLoopOutputType newSteerMotorClosedLoopOutput)
 Modifies the SteerMotorClosedLoopOutput parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveMotorClosedLoopOutput (ClosedLoopOutputType newDriveMotorClosedLoopOutput)
 Modifies the DriveMotorClosedLoopOutput parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSlipCurrent (units::current::ampere_t newSlipCurrent)
 Modifies the SlipCurrent parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSpeedAt12Volts (units::velocity::meters_per_second_t newSpeedAt12Volts)
 Modifies the SpeedAt12Volts parameter and returns itself.
 
constexpr SwerveModuleConstantsWithFeedbackSource (SteerFeedbackType newFeedbackSource)
 Modifies the FeedbackSource parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveMotorInitialConfigs (const configs::TalonFXConfiguration &newDriveMotorInitialConfigs)
 Modifies the DriveMotorInitialConfigs parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerMotorInitialConfigs (const configs::TalonFXConfiguration &newSteerMotorInitialConfigs)
 Modifies the SteerMotorInitialConfigs parameter and returns itself.
 
constexpr SwerveModuleConstantsWithCANcoderInitialConfigs (const configs::CANcoderConfiguration &newCANcoderInitialConfigs)
 Modifies the CANcoderInitialConfigs parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerInertia (units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
 Modifies the SteerInertia parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveInertia (units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
 Modifies the DriveInertia parameter and returns itself.
 
constexpr SwerveModuleConstantsWithSteerFrictionVoltage (units::voltage::volt_t newSteerFrictionVoltage)
 Modifies the SteerFrictionVoltage parameter and returns itself.
 
constexpr SwerveModuleConstantsWithDriveFrictionVoltage (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.
 

Detailed Description

All constants for a swerve module.

Constructor & Destructor Documentation

◆ SwerveModuleConstants()

constexpr ctre::phoenix6::swerve::SwerveModuleConstants::SwerveModuleConstants ( )
constexprdefault

Member Function Documentation

◆ WithCANcoderId()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithCANcoderId ( int newCANcoderId)
inlineconstexpr

Modifies the CANcoderId parameter and returns itself.

CAN ID of the CANcoder used for azimuth.

Parameters
newCANcoderIdParameter to modify
Returns
this object

◆ WithCANcoderInitialConfigs()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithCANcoderInitialConfigs ( const configs::CANcoderConfiguration & newCANcoderInitialConfigs)
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:

Parameters
newCANcoderInitialConfigsParameter to modify
Returns
this object

◆ WithCANcoderInverted()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithCANcoderInverted ( bool newCANcoderInverted)
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).

Parameters
newCANcoderInvertedParameter to modify
Returns
this object

◆ WithCANcoderOffset()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithCANcoderOffset ( units::angle::turn_t newCANcoderOffset)
inlineconstexpr

Modifies the CANcoderOffset parameter and returns itself.

Offset of the CANcoder.

Parameters
newCANcoderOffsetParameter to modify
Returns
this object

◆ WithCouplingGearRatio()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithCouplingGearRatio ( units::dimensionless::scalar_t newCouplingGearRatio)
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.

Parameters
newCouplingGearRatioParameter to modify
Returns
this object

◆ WithDriveFrictionVoltage()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveFrictionVoltage ( units::voltage::volt_t newDriveFrictionVoltage)
inlineconstexpr

Modifies the DriveFrictionVoltage parameter and returns itself.

Simulated drive voltage required to overcome friction.

Parameters
newDriveFrictionVoltageParameter to modify
Returns
this object

◆ WithDriveInertia()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveInertia ( units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
inlineconstexpr

Modifies the DriveInertia parameter and returns itself.

Simulated drive inertia.

Parameters
newDriveInertiaParameter to modify
Returns
this object

◆ WithDriveMotorClosedLoopOutput()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveMotorClosedLoopOutput ( ClosedLoopOutputType newDriveMotorClosedLoopOutput)
inlineconstexpr

Modifies the DriveMotorClosedLoopOutput parameter and returns itself.

The closed-loop output type to use for the drive motors.

Parameters
newDriveMotorClosedLoopOutputParameter to modify
Returns
this object

◆ WithDriveMotorGains()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveMotorGains ( const configs::Slot0Configs & newDriveMotorGains)
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).

Parameters
newDriveMotorGainsParameter to modify
Returns
this object

◆ WithDriveMotorGearRatio()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveMotorGearRatio ( units::dimensionless::scalar_t newDriveMotorGearRatio)
inlineconstexpr

Modifies the DriveMotorGearRatio parameter and returns itself.

Gear ratio between the drive motor and the wheel.

Parameters
newDriveMotorGearRatioParameter to modify
Returns
this object

◆ WithDriveMotorId()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveMotorId ( int newDriveMotorId)
inlineconstexpr

Modifies the DriveMotorId parameter and returns itself.

CAN ID of the drive motor.

Parameters
newDriveMotorIdParameter to modify
Returns
this object

◆ WithDriveMotorInitialConfigs()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveMotorInitialConfigs ( const configs::TalonFXConfiguration & newDriveMotorInitialConfigs)
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:

Parameters
newDriveMotorInitialConfigsParameter to modify
Returns
this object

◆ WithDriveMotorInverted()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithDriveMotorInverted ( bool newDriveMotorInverted)
inlineconstexpr

Modifies the DriveMotorInverted parameter and returns itself.

True if the drive motor is inverted.

Parameters
newDriveMotorInvertedParameter to modify
Returns
this object

◆ WithFeedbackSource()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithFeedbackSource ( SteerFeedbackType newFeedbackSource)
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.

Parameters
newFeedbackSourceParameter to modify
Returns
this object

◆ WithLocationX()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithLocationX ( units::length::meter_t newLocationX)
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.

Parameters
newLocationXParameter to modify
Returns
this object

◆ WithLocationY()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithLocationY ( units::length::meter_t newLocationY)
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.

Parameters
newLocationYParameter to modify
Returns
this object

◆ WithSlipCurrent()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSlipCurrent ( units::current::ampere_t newSlipCurrent)
inlineconstexpr

Modifies the SlipCurrent parameter and returns itself.

The maximum amount of stator current the drive motors can apply without slippage.

Parameters
newSlipCurrentParameter to modify
Returns
this object

◆ WithSpeedAt12Volts()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSpeedAt12Volts ( units::velocity::meters_per_second_t newSpeedAt12Volts)
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.

Parameters
newSpeedAt12VoltsParameter to modify
Returns
this object

◆ WithSteerFrictionVoltage()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerFrictionVoltage ( units::voltage::volt_t newSteerFrictionVoltage)
inlineconstexpr

Modifies the SteerFrictionVoltage parameter and returns itself.

Simulated steer voltage required to overcome friction.

Parameters
newSteerFrictionVoltageParameter to modify
Returns
this object

◆ WithSteerInertia()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerInertia ( units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
inlineconstexpr

Modifies the SteerInertia parameter and returns itself.

Simulated azimuthal inertia.

Parameters
newSteerInertiaParameter to modify
Returns
this object

◆ WithSteerMotorClosedLoopOutput()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerMotorClosedLoopOutput ( ClosedLoopOutputType newSteerMotorClosedLoopOutput)
inlineconstexpr

Modifies the SteerMotorClosedLoopOutput parameter and returns itself.

The closed-loop output type to use for the steer motors.

Parameters
newSteerMotorClosedLoopOutputParameter to modify
Returns
this object

◆ WithSteerMotorGains()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerMotorGains ( const configs::Slot0Configs & newSteerMotorGains)
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).

Parameters
newSteerMotorGainsParameter to modify
Returns
this object

◆ WithSteerMotorGearRatio()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerMotorGearRatio ( units::dimensionless::scalar_t newSteerMotorGearRatio)
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.

Parameters
newSteerMotorGearRatioParameter to modify
Returns
this object

◆ WithSteerMotorId()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerMotorId ( int newSteerMotorId)
inlineconstexpr

Modifies the SteerMotorId parameter and returns itself.

CAN ID of the steer motor.

Parameters
newSteerMotorIdParameter to modify
Returns
this object

◆ WithSteerMotorInitialConfigs()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerMotorInitialConfigs ( const configs::TalonFXConfiguration & newSteerMotorInitialConfigs)
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:

Parameters
newSteerMotorInitialConfigsParameter to modify
Returns
this object

◆ WithSteerMotorInverted()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithSteerMotorInverted ( bool newSteerMotorInverted)
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.

Parameters
newSteerMotorInvertedParameter to modify
Returns
this object

◆ WithWheelRadius()

constexpr SwerveModuleConstants & ctre::phoenix6::swerve::SwerveModuleConstants::WithWheelRadius ( units::length::meter_t newWheelRadius)
inlineconstexpr

Modifies the WheelRadius parameter and returns itself.

Radius of the driving wheel in meters.

Parameters
newWheelRadiusParameter to modify
Returns
this object

Member Data Documentation

◆ CANcoderId

int ctre::phoenix6::swerve::SwerveModuleConstants::CANcoderId = 0

CAN ID of the CANcoder used for azimuth.

◆ CANcoderInitialConfigs

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:

◆ CANcoderInverted

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).

◆ CANcoderOffset

units::angle::turn_t ctre::phoenix6::swerve::SwerveModuleConstants::CANcoderOffset = 0_tr

Offset of the CANcoder.

◆ CouplingGearRatio

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.

◆ DriveFrictionVoltage

units::voltage::volt_t ctre::phoenix6::swerve::SwerveModuleConstants::DriveFrictionVoltage = 0.25_V

Simulated drive voltage required to overcome friction.

◆ DriveInertia

units::moment_of_inertia::kilogram_square_meter_t ctre::phoenix6::swerve::SwerveModuleConstants::DriveInertia = 0.001_kg_sq_m

Simulated drive inertia.

◆ DriveMotorClosedLoopOutput

ClosedLoopOutputType ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorClosedLoopOutput = ClosedLoopOutputType::Voltage

The closed-loop output type to use for the drive motors.

◆ DriveMotorGains

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).

◆ DriveMotorGearRatio

units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorGearRatio = 0

Gear ratio between the drive motor and the wheel.

◆ DriveMotorId

int ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorId = 0

CAN ID of the drive motor.

◆ DriveMotorInitialConfigs

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:

◆ DriveMotorInverted

bool ctre::phoenix6::swerve::SwerveModuleConstants::DriveMotorInverted = false

True if the drive motor is inverted.

◆ FeedbackSource

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.

◆ LocationX

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.

◆ LocationY

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.

◆ SlipCurrent

units::current::ampere_t ctre::phoenix6::swerve::SwerveModuleConstants::SlipCurrent = 120_A

The maximum amount of stator current the drive motors can apply without slippage.

◆ SpeedAt12Volts

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.

◆ SteerFrictionVoltage

units::voltage::volt_t ctre::phoenix6::swerve::SwerveModuleConstants::SteerFrictionVoltage = 0.25_V

Simulated steer voltage required to overcome friction.

◆ SteerInertia

units::moment_of_inertia::kilogram_square_meter_t ctre::phoenix6::swerve::SwerveModuleConstants::SteerInertia = 0.00001_kg_sq_m

Simulated azimuthal inertia.

◆ SteerMotorClosedLoopOutput

ClosedLoopOutputType ctre::phoenix6::swerve::SwerveModuleConstants::SteerMotorClosedLoopOutput = ClosedLoopOutputType::Voltage

The closed-loop output type to use for the steer motors.

◆ SteerMotorGains

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).

◆ SteerMotorGearRatio

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.

◆ SteerMotorId

int ctre::phoenix6::swerve::SwerveModuleConstants::SteerMotorId = 0

CAN ID of the steer motor.

◆ SteerMotorInitialConfigs

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:

◆ SteerMotorInverted

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.

◆ WheelRadius

units::length::meter_t ctre::phoenix6::swerve::SwerveModuleConstants::WheelRadius = 0_m

Radius of the driving wheel in meters.


The documentation for this struct was generated from the following file: