CTRE Phoenix 6 C++ 24.50.0-alpha-2
ctre::phoenix6::swerve::SwerveModuleConstantsFactory Struct Reference

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 SwerveModuleConstantsFactoryWithDriveMotorGearRatio (units::dimensionless::scalar_t newDriveMotorGearRatio)
 Modifies the DriveMotorGearRatio parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSteerMotorGearRatio (units::dimensionless::scalar_t newSteerMotorGearRatio)
 Modifies the SteerMotorGearRatio parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithCouplingGearRatio (units::dimensionless::scalar_t newCouplingGearRatio)
 Modifies the CouplingGearRatio parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithWheelRadius (units::length::meter_t newWheelRadius)
 Modifies the WheelRadius parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSteerMotorGains (configs::Slot0Configs newSteerMotorGains)
 Modifies the SteerMotorGains parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithDriveMotorGains (configs::Slot0Configs newDriveMotorGains)
 Modifies the DriveMotorGains parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSteerMotorClosedLoopOutput (ClosedLoopOutputType newSteerMotorClosedLoopOutput)
 Modifies the SteerMotorClosedLoopOutput parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithDriveMotorClosedLoopOutput (ClosedLoopOutputType newDriveMotorClosedLoopOutput)
 Modifies the DriveMotorClosedLoopOutput parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSlipCurrent (units::current::ampere_t newSlipCurrent)
 Modifies the SlipCurrent parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSpeedAt12Volts (units::velocity::meters_per_second_t newSpeedAt12Volts)
 Modifies the SpeedAt12Volts parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithFeedbackSource (SteerFeedbackType newFeedbackSource)
 Modifies the FeedbackSource parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithDriveMotorInitialConfigs (configs::TalonFXConfiguration newDriveMotorInitialConfigs)
 Modifies the DriveMotorInitialConfigs parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSteerMotorInitialConfigs (configs::TalonFXConfiguration newSteerMotorInitialConfigs)
 Modifies the SteerMotorInitialConfigs parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithCANcoderInitialConfigs (configs::CANcoderConfiguration newCANcoderInitialConfigs)
 Modifies the CANcoderInitialConfigs parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSteerInertia (units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
 Modifies the SteerInertia parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithDriveInertia (units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
 Modifies the DriveInertia parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithSteerFrictionVoltage (units::voltage::volt_t newSteerFrictionVoltage)
 Modifies the SteerFrictionVoltage parameter and returns itself. More...
 
constexpr SwerveModuleConstantsFactoryWithDriveFrictionVoltage (units::voltage::volt_t newDriveFrictionVoltage)
 Modifies the DriveFrictionVoltage parameter and returns itself. More...
 
constexpr SwerveModuleConstants CreateModuleConstants (int steerMotorId, int driveMotorId, int cancoderId, units::angle::turn_t cancoderOffset, units::length::meter_t locationX, units::length::meter_t locationY, bool driveMotorInverted, bool steerMotorInverted) const
 Creates the constants for a swerve module with the given properties. More...
 

Public Attributes

units::dimensionless::scalar_t DriveMotorGearRatio = 0
 Gear ratio between the drive motor and the wheel. More...
 
units::dimensionless::scalar_t SteerMotorGearRatio = 0
 Gear ratio between the steer motor and the CANcoder. More...
 
units::dimensionless::scalar_t CouplingGearRatio = 0
 Coupled gear ratio between the CANcoder and the drive motor. More...
 
units::length::meter_t WheelRadius = 0_m
 Radius of the driving wheel in meters. More...
 
configs::Slot0Configs SteerMotorGains = configs::Slot0Configs{}
 The steer motor closed-loop gains. More...
 
configs::Slot0Configs DriveMotorGains = configs::Slot0Configs{}
 The drive motor closed-loop gains. More...
 
ClosedLoopOutputType SteerMotorClosedLoopOutput = ClosedLoopOutputType::Voltage
 The closed-loop output type to use for the steer motors. More...
 
ClosedLoopOutputType DriveMotorClosedLoopOutput = ClosedLoopOutputType::Voltage
 The closed-loop output type to use for the drive motors. More...
 
units::current::ampere_t SlipCurrent = 120_A
 The maximum amount of stator current the drive motors can apply without slippage. More...
 
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. More...
 
SteerFeedbackType FeedbackSource = SteerFeedbackType::FusedCANcoder
 Choose how the feedback sensors should be configured. More...
 
configs::TalonFXConfiguration DriveMotorInitialConfigs = configs::TalonFXConfiguration{}
 The initial configs used to configure the drive motor of the swerve module. More...
 
configs::TalonFXConfiguration SteerMotorInitialConfigs = configs::TalonFXConfiguration{}
 The initial configs used to configure the steer motor of the swerve module. More...
 
configs::CANcoderConfiguration CANcoderInitialConfigs = configs::CANcoderConfiguration{}
 The initial configs used to configure the CANcoder of the swerve module. More...
 
units::moment_of_inertia::kilogram_square_meter_t SteerInertia = 0.00001_kg_sq_m
 Simulated azimuthal inertia. More...
 
units::moment_of_inertia::kilogram_square_meter_t DriveInertia = 0.001_kg_sq_m
 Simulated drive inertia. More...
 
units::voltage::volt_t SteerFrictionVoltage = 0.25_V
 Simulated steer voltage required to overcome friction. More...
 
units::voltage::volt_t DriveFrictionVoltage = 0.25_V
 Simulated drive voltage required to overcome friction. More...
 

Detailed Description

Constants that are common across the swerve modules, used for creating instances of module-specific SwerveModuleConstants.

Constructor & Destructor Documentation

◆ SwerveModuleConstantsFactory()

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

Member Function Documentation

◆ CreateModuleConstants()

constexpr SwerveModuleConstants ctre::phoenix6::swerve::SwerveModuleConstantsFactory::CreateModuleConstants ( int  steerMotorId,
int  driveMotorId,
int  cancoderId,
units::angle::turn_t  cancoderOffset,
units::length::meter_t  locationX,
units::length::meter_t  locationY,
bool  driveMotorInverted,
bool  steerMotorInverted 
) const
inlineconstexpr

Creates the constants for a swerve module with the given properties.

Parameters
steerMotorIdCAN ID of the steer motor.
driveMotorIdCAN ID of the drive motor.
cancoderIdCAN ID of the CANcoder used for azimuth.
cancoderOffsetOffset of the CANcoder.
locationXThe location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot.
locationYThe location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot.
driveMotorInvertedTrue if the drive motor is inverted.
steerMotorInvertedTrue if the steer motor is inverted from the CANcoder.
Returns
Constants for the swerve module

◆ WithCANcoderInitialConfigs()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::WithCANcoderInitialConfigs ( 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

◆ WithCouplingGearRatio()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::WithDriveMotorGains ( 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.

Parameters
newDriveMotorGainsParameter to modify
Returns
this object

◆ WithDriveMotorGearRatio()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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

◆ WithDriveMotorInitialConfigs()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::WithDriveMotorInitialConfigs ( 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

◆ WithFeedbackSource()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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

◆ WithSlipCurrent()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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 SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::WithSteerMotorGains ( 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.

Parameters
newSteerMotorGainsParameter to modify
Returns
this object

◆ WithSteerMotorGearRatio()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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

◆ WithSteerMotorInitialConfigs()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::WithSteerMotorInitialConfigs ( 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

◆ WithWheelRadius()

constexpr SwerveModuleConstantsFactory & ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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

◆ CANcoderInitialConfigs

configs::CANcoderConfiguration ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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:

◆ CouplingGearRatio

units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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::SwerveModuleConstantsFactory::DriveFrictionVoltage = 0.25_V

Simulated drive voltage required to overcome friction.

◆ DriveInertia

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

Simulated drive inertia.

◆ DriveMotorClosedLoopOutput

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

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

◆ DriveMotorGains

configs::Slot0Configs ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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.

◆ DriveMotorGearRatio

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

Gear ratio between the drive motor and the wheel.

◆ DriveMotorInitialConfigs

configs::TalonFXConfiguration ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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:

◆ FeedbackSource

SteerFeedbackType ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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.

◆ SlipCurrent

units::current::ampere_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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::SwerveModuleConstantsFactory::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::SwerveModuleConstantsFactory::SteerFrictionVoltage = 0.25_V

Simulated steer voltage required to overcome friction.

◆ SteerInertia

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

Simulated azimuthal inertia.

◆ SteerMotorClosedLoopOutput

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

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

◆ SteerMotorGains

configs::Slot0Configs ctre::phoenix6::swerve::SwerveModuleConstantsFactory::SteerMotorGains = configs::Slot0Configs{}

The steer motor closed-loop gains.

The steer motor uses the control ouput type specified by SteerMotorClosedLoopOutput and any SwerveModule::SteerRequestType.

◆ SteerMotorGearRatio

units::dimensionless::scalar_t ctre::phoenix6::swerve::SwerveModuleConstantsFactory::SteerMotorGearRatio = 0

Gear ratio between the steer motor and the CANcoder.

For example, the SDS Mk4 has a steering ratio of 12.8.

◆ SteerMotorInitialConfigs

configs::TalonFXConfiguration ctre::phoenix6::swerve::SwerveModuleConstantsFactory::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:

◆ WheelRadius

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

Radius of the driving wheel in meters.


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