phoenix6.swerve.swerve_module
¶
Module Contents¶
Attributes¶
- phoenix6.swerve.swerve_module.DriveMotorT¶
- phoenix6.swerve.swerve_module.SteerMotorT¶
- phoenix6.swerve.swerve_module.EncoderT¶
- class phoenix6.swerve.swerve_module.SwerveModule(drive_motor_type: type[DriveMotorT], steer_motor_type: type[SteerMotorT], encoder_type: type[EncoderT], constants: phoenix6.swerve.swerve_module_constants.SwerveModuleConstants, canbus_name: str, drivetrain_id: int, index: int)¶
Bases:
Generic
[DriveMotorT
,SteerMotorT
,EncoderT
]Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
This class handles the hardware devices and configures them for swerve module operation using the Phoenix 6 API.
This class constructs hardware devices internally, so the user only specifies the constants (IDs, PID gains, gear ratios, etc). Getters for these hardware devices are available.
- Parameters:
drive_motor_type (type[DriveMotorT]) – Type of the drive motor
steer_motor_type (type[SteerMotorT]) – Type of the steer motor
encoder_type (type[EncoderT]) – Type of the azimuth encoder
constants (SwerveModuleConstants) – Constants used to construct the module
canbus_name (str) – The name of the CAN bus this module is on
drivetrain_id (int) – ID of the swerve drivetrain
index (int) – Index of this swerve module
- class SteerRequestType(*args, **kwds)¶
Bases:
enum.Enum
All possible control requests for the module steer motor.
- MOTION_MAGIC_EXPO = 0¶
Control the drive motor using a Motion Magic® Expo request. The control output type is determined by SwerveModuleConstants.SteerMotorClosedLoopOutput
- POSITION = 1¶
Control the drive motor using an unprofiled position request. The control output type is determined by SwerveModuleConstants.SteerMotorClosedLoopOutput
- class DriveRequestType(*args, **kwds)¶
Bases:
enum.Enum
Create a collection of name/value pairs.
Example enumeration:
>>> class Color(Enum): ... RED = 1 ... BLUE = 2 ... GREEN = 3
Access them by:
attribute access:
>>> Color.RED <Color.RED: 1>
value lookup:
>>> Color(1) <Color.RED: 1>
name lookup:
>>> Color['RED'] <Color.RED: 1>
Enumerations can be iterated over, and know how many members they have:
>>> len(Color) 3
>>> list(Color) [<Color.RED: 1>, <Color.BLUE: 2>, <Color.GREEN: 3>]
Methods can be added to enumerations, and members can have their own attributes – see the documentation for details.
- OPEN_LOOP_VOLTAGE = 0¶
Control the drive motor using an open-loop voltage request.
- VELOCITY = 1¶
Control the drive motor using a velocity closed-loop request. The control output type is determined by SwerveModuleConstants.DriveMotorClosedLoopOutput
- class ModuleRequest¶
Contains everything the swerve module needs to apply a request.
- state¶
Unoptimized speed and direction the module should target.
- wheel_force_feedforward_x: phoenix6.units.newton = 0.0¶
Robot-centric wheel force feedforward to apply in the X direction. X is defined as forward according to WPILib convention, so this determines the forward force to apply.
This force should include friction applied to the ground.
- wheel_force_feedforward_y: phoenix6.units.newton = 0.0¶
Robot-centric wheel force feedforward to apply in the Y direction. Y is defined as to the left according to WPILib convention, so this determines the force to apply to the left.
This force should include friction applied to the ground.
- drive_request¶
The type of control request to use for the drive motor.
- steer_request¶
The type of control request to use for the steer motor.
- update_period: second = 0.0¶
The update period of the module request. Setting this to a non-zero value adds a velocity feedforward to the steer motor.
- enable_foc = True¶
When using Voltage-based control, set to true (default) to use FOC commutation (requires Phoenix Pro), which increases peak power by ~15%. Set to false to use trapezoidal commutation. This is ignored when using Torque-based control, which always uses FOC.
FOC improves motor performance by leveraging torque (current) control. However, this may be inconvenient for applications that require specifying duty cycle or voltage. CTR-Electronics has developed a hybrid method that combines the performances gains of FOC while still allowing applications to provide duty cycle or voltage demand. This not to be confused with simple sinusoidal control or phase voltage control which lacks the performance gains.
- with_state(new_state: SwerveModuleState) SwerveModule ¶
Modifies the state parameter and returns itself.
Unoptimized speed and direction the module should target.
- Parameters:
new_state (SwerveModuleState) – Parameter to modify
- Returns:
Itself
- Return type:
- with_wheel_force_feedforward_x(new_wheel_force_feedforward_x: phoenix6.units.newton) SwerveModule ¶
Modifies the wheel_force_feedforward_x parameter and returns itself.
Robot-centric wheel force feedforward to apply in the X direction. X is defined as forward according to WPILib convention, so this determines the forward force to apply.
This force should include friction applied to the ground.
- Parameters:
wheel_force_feedforward_x (newton) – Parameter to modify
- Returns:
Itself
- Return type:
- with_wheel_force_feedforward_y(new_wheel_force_feedforward_y: phoenix6.units.newton) SwerveModule ¶
Modifies the wheel_force_feedforward_y parameter and returns itself.
Robot-centric wheel force feedforward to apply in the Y direction. Y is defined as to the left according to WPILib convention, so this determines the force to apply to the left.
This force should include friction applied to the ground.
- Parameters:
wheel_force_feedforward_y (newton) – Parameter to modify
- Returns:
Itself
- Return type:
- with_drive_request(new_drive_request: SwerveModule) SwerveModule ¶
Modifies the drive_request parameter and returns itself.
The type of control request to use for the drive motor.
- Parameters:
new_drive_request (SwerveModule.DriveRequestType) – Parameter to modify
- Returns:
Itself
- Return type:
- with_steer_request(new_steer_request: SwerveModule) SwerveModule ¶
Modifies the steer_request parameter and returns itself.
The type of control request to use for the steer motor.
- Parameters:
new_steer_request (SwerveModule.SteerRequestType) – Parameter to modify
- Returns:
Itself
- Return type:
- with_update_period(new_update_period: second) SwerveModule ¶
Modifies the update_period parameter and returns itself.
The update period of the module request. Setting this to a non-zero value adds a velocity feedforward to the steer motor.
- Parameters:
new_update_period (second) – Parameter to modify
- Returns:
Itself
- Return type:
- with_enable_foc(new_enable_foc: bool) SwerveModule ¶
Modifies the enable_foc parameter and returns itself.
When using Voltage-based control, set to true (default) to use FOC commutation (requires Phoenix Pro), which increases peak power by ~15%. Set to false to use trapezoidal commutation. This is ignored when using Torque-based control, which always uses FOC.
FOC improves motor performance by leveraging torque (current) control. However, this may be inconvenient for applications that require specifying duty cycle or voltage. CTR-Electronics has developed a hybrid method that combines the performances gains of FOC while still allowing applications to provide duty cycle or voltage demand. This not to be confused with simple sinusoidal control or phase voltage control which lacks the performance gains.
- Parameters:
new_enable_foc (bool) – Parameter to modify
- Returns:
Itself
- Return type:
- property drive_closed_loop_output_type: phoenix6.swerve.swerve_module_constants.ClosedLoopOutputType¶
Gets the closed-loop output type to use for the drive motor.
- Returns:
Drive motor closed-loop output type
- Return type:
- property steer_closed_loop_output_type: phoenix6.swerve.swerve_module_constants.ClosedLoopOutputType¶
Gets the closed-loop output type to use for the steer motor.
- Returns:
Steer motor closed-loop output type
- Return type:
- property drive_motor: DriveMotorT¶
Gets this module’s Drive Motor reference.
This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
- Returns:
This module’s Drive Motor reference
- Return type:
DriveMotorT
- property steer_motor: SteerMotorT¶
Gets this module’s Steer Motor reference.
This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
- Returns:
This module’s Steer Motor reference
- Return type:
SteerMotorT
- property encoder: EncoderT¶
Gets this module’s azimuth encoder reference.
This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
- Returns:
This module’s azimuth encoder reference
- Return type:
EncoderT
- apply(module_request: ModuleRequest)¶
- apply(drive_request: phoenix6.hardware.parent_device.SupportsSendRequest, steer_request: phoenix6.hardware.parent_device.SupportsSendRequest)
- get_position(refresh: bool) SwerveModulePosition ¶
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compensated values.
This function is blocking when it performs a refresh.
- Parameters:
refresh (bool) – True if the signals should be refreshed
- Returns:
SwerveModulePosition containing this module’s state
- Return type:
SwerveModulePosition
- get_cached_position() SwerveModulePosition ¶
Gets the last cached swerve module position. This differs from get_position in that it will not perform any latency compensation or refresh the signals.
- Returns:
Last cached SwerveModulePosition
- Return type:
SwerveModulePosition
- get_current_state() SwerveModuleState ¶
Get the current state of the module.
This is typically used for telemetry, as the SwerveModulePosition is used for odometry.
- Returns:
Current state of the module
- Return type:
- get_target_state() SwerveModuleState ¶
Get the target state of the module.
This is typically used for telemetry.
- Returns:
Target state of the module
- Return type:
- reset_position()¶
Resets this module’s drive motor position to 0 rotations.