phoenix6.swerve.requests

Module Contents

Attributes

phoenix6.swerve.requests.USE_WPILIB = True
class phoenix6.swerve.requests.ForwardPerspectiveValue(*args, **kwds)

Bases: enum.Enum

In field-centric control, the direction of “forward” is sometimes different depending on perspective. This addresses which forward to use.

OPERATOR_PERSPECTIVE = 0

“Forward” (positive X) is determined from the operator’s perspective. This is important for most teleop driven field-centric requests, where positive X means to drive away from the operator.

Important: Users must specify the operator_perspective in the SwerveDrivetrain object

BLUE_ALLIANCE = 1

“Forward” (positive X) is always from the perspective of the blue alliance (i.e. towards the red alliance). This is important in situations such as path following where positive X is always from the blue alliance perspective, regardless of where the operator is physically located.

class phoenix6.swerve.requests.SwerveRequest

Bases: Protocol

Container for all the Swerve Requests. Use this to find all applicable swerve drive requests.

This is also an interface common to all swerve drive control requests that allow the request to calculate the state to apply to the modules.

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.NativeSwerveRequest

Bases: SwerveRequest, Protocol

Swerve requests implemented in native code.

class phoenix6.swerve.requests.Idle

Bases: NativeSwerveRequest

Does nothing to the swerve module state. This is the default state of a newly created swerve drive mechanism.

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.SwerveDriveBrake

Bases: NativeSwerveRequest

Sets the swerve drive module states to point inward on the robot in an “X” fashion, creating a natural brake which will oppose any motion.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) SwerveDriveBrake

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

SwerveDriveBrake

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) SwerveDriveBrake

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

SwerveDriveBrake

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.FieldCentric

Bases: NativeSwerveRequest

Drives the swerve drivetrain in a field-centric manner.

When users use this request, they specify the direction the robot should travel oriented against the field, and the rate at which their robot should rotate about the center of the robot.

An example scenario is that the robot is oriented to the east, the VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In this scenario, the robot would drive northward at 5 m/s and turn counterclockwise at 0.5 rad/s.

velocity_x: phoenix6.units.meters_per_second = 0

The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

velocity_y: phoenix6.units.meters_per_second = 0

The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

rotational_rate: phoenix6.units.radians_per_second = 0

The angular rate to rotate at, in radians per second. Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.

deadband: phoenix6.units.meters_per_second = 0

The allowable deadband of the request, in m/s.

rotational_deadband: phoenix6.units.radians_per_second = 0

The rotational deadband of the request, in radians per second.

center_of_rotation: Translation2d

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

desaturate_wheel_speeds: bool = True

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

forward_perspective: ForwardPerspectiveValue

The perspective to use when determining which direction is forward.

with_velocity_x(new_velocity_x: phoenix6.units.meters_per_second) FieldCentric

Modifies the velocity_x parameter and returns itself.

The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

Parameters:

new_velocity_x (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_velocity_y(new_velocity_y: phoenix6.units.meters_per_second) FieldCentric

Modifies the velocity_y parameter and returns itself.

The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

Parameters:

new_velocity_y (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_rotational_rate(new_rotational_rate: phoenix6.units.radians_per_second) FieldCentric

Modifies the rotational_rate parameter and returns itself.

The angular rate to rotate at, in radians per second. Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.

Parameters:

new_rotational_rate (radians_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_deadband(new_deadband: phoenix6.units.meters_per_second) FieldCentric

Modifies the deadband parameter and returns itself.

The allowable deadband of the request, in m/s.

Parameters:

new_deadband (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_rotational_deadband(new_rotational_deadband: phoenix6.units.radians_per_second) FieldCentric

Modifies the rotational_deadband parameter and returns itself.

The rotational deadband of the request, in radians per second.

Parameters:

new_rotational_deadband (radians_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_center_of_rotation(new_center_of_rotation: Translation2d) FieldCentric

Modifies the center_of_rotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters:

new_center_of_rotation (Translation2d) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) FieldCentric

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) FieldCentric

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_desaturate_wheel_speeds(new_desaturate_wheel_speeds: bool) FieldCentric

Modifies the desaturate_wheel_speeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

Parameters:

new_desaturate_wheel_speeds (bool) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

with_forward_perspective(new_forward_perspective: ForwardPerspectiveValue) FieldCentric

Modifies the forward_perspective parameter and returns itself.

The perspective to use when determining which direction is forward.

Parameters:

new_forward_perspective (ForwardPerspectiveValue) – Parameter to modify

Returns:

this object

Return type:

FieldCentric

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.RobotCentric

Bases: NativeSwerveRequest

Drives the swerve drivetrain in a robot-centric manner.

When users use this request, they specify the direction the robot should travel oriented against the robot itself, and the rate at which their robot should rotate about the center of the robot.

An example scenario is that the robot is oriented to the east, the VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In this scenario, the robot would drive eastward at 5 m/s and turn counterclockwise at 0.5 rad/s.

velocity_x: phoenix6.units.meters_per_second = 0

The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

velocity_y: phoenix6.units.meters_per_second = 0

The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

rotational_rate: phoenix6.units.radians_per_second = 0

The angular rate to rotate at, in radians per second. Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.

deadband: phoenix6.units.meters_per_second = 0

The allowable deadband of the request, in m/s.

rotational_deadband: phoenix6.units.radians_per_second = 0

The rotational deadband of the request, in radians per second.

center_of_rotation: Translation2d

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

desaturate_wheel_speeds: bool = True

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

with_velocity_x(new_velocity_x: phoenix6.units.meters_per_second) RobotCentric

Modifies the velocity_x parameter and returns itself.

The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

Parameters:

new_velocity_x (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_velocity_y(new_velocity_y: phoenix6.units.meters_per_second) RobotCentric

Modifies the velocity_y parameter and returns itself.

The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

Parameters:

new_velocity_y (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_rotational_rate(new_rotational_rate: phoenix6.units.radians_per_second) RobotCentric

Modifies the rotational_rate parameter and returns itself.

The angular rate to rotate at, in radians per second. Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.

Parameters:

new_rotational_rate (radians_per_second) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_deadband(new_deadband: phoenix6.units.meters_per_second) RobotCentric

Modifies the deadband parameter and returns itself.

The allowable deadband of the request, in m/s.

Parameters:

new_deadband (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_rotational_deadband(new_rotational_deadband: phoenix6.units.radians_per_second) RobotCentric

Modifies the rotational_deadband parameter and returns itself.

The rotational deadband of the request, in radians per second.

Parameters:

new_rotational_deadband (radians_per_second) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_center_of_rotation(new_center_of_rotation: Translation2d) RobotCentric

Modifies the center_of_rotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters:

new_center_of_rotation (Translation2d) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) RobotCentric

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) RobotCentric

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

with_desaturate_wheel_speeds(new_desaturate_wheel_speeds: bool) RobotCentric

Modifies the desaturate_wheel_speeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

Parameters:

new_desaturate_wheel_speeds (bool) – Parameter to modify

Returns:

this object

Return type:

RobotCentric

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.PointWheelsAt

Bases: NativeSwerveRequest

Sets the swerve drive modules to point to a specified direction.

module_direction: Rotation2d

The direction to point the modules toward. This direction is still optimized to what the module was previously at.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

with_module_direction(new_module_direction: Rotation2d) PointWheelsAt

Modifies the module_direction parameter and returns itself.

The direction to point the modules toward. This direction is still optimized to what the module was previously at.

Parameters:

new_module_direction (Rotation2d) – Parameter to modify

Returns:

this object

Return type:

PointWheelsAt

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) PointWheelsAt

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

PointWheelsAt

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) PointWheelsAt

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

PointWheelsAt

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.ApplyRobotSpeeds

Bases: NativeSwerveRequest

Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.

speeds: ChassisSpeeds

The robot-centric chassis speeds to apply to the drivetrain.

wheel_force_feedforwards_x: list[phoenix6.units.newton] = []

Robot-centric wheel force feedforwards to apply in the X direction, in newtons. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

wheel_force_feedforwards_y: list[phoenix6.units.newton] = []

Robot-centric wheel force feedforwards to apply in the Y direction, in newtons. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

center_of_rotation: Translation2d

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

desaturate_wheel_speeds: bool = True

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

with_speeds(new_speeds: ChassisSpeeds) ApplyRobotSpeeds

Modifies the speeds parameter and returns itself.

The robot-centric chassis speeds to apply to the drivetrain.

Parameters:

new_speeds (ChassisSpeeds) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

with_wheel_force_feedforwards_x(new_wheel_force_feedforwards_x: list[phoenix6.units.newton]) ApplyRobotSpeeds

Modifies the wheel_force_feedforwards_x parameter and returns itself.

Robot-centric wheel force feedforwards to apply in the X direction, in newtons. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters:

new_wheel_force_feedforwards_x (list[newton]) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

with_wheel_force_feedforwards_y(new_wheel_force_feedforwards_y: list[phoenix6.units.newton]) ApplyRobotSpeeds

Modifies the wheel_force_feedforwards_y parameter and returns itself.

Robot-centric wheel force feedforwards to apply in the Y direction, in newtons. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters:

new_wheel_force_feedforwards_y (list[newton]) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

with_center_of_rotation(new_center_of_rotation: Translation2d) ApplyRobotSpeeds

Modifies the center_of_rotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters:

new_center_of_rotation (Translation2d) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) ApplyRobotSpeeds

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) ApplyRobotSpeeds

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

with_desaturate_wheel_speeds(new_desaturate_wheel_speeds: bool) ApplyRobotSpeeds

Modifies the desaturate_wheel_speeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

Parameters:

new_desaturate_wheel_speeds (bool) – Parameter to modify

Returns:

this object

Return type:

ApplyRobotSpeeds

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.ApplyFieldSpeeds

Bases: NativeSwerveRequest

Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain.

speeds: ChassisSpeeds

The field-centric chassis speeds to apply to the drivetrain.

wheel_force_feedforwards_x: list[phoenix6.units.newton] = []

Field-centric wheel force feedforwards to apply in the X direction, in newtons. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

wheel_force_feedforwards_y: list[phoenix6.units.newton] = []

Field-centric wheel force feedforwards to apply in the Y direction, in newtons. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

center_of_rotation: Translation2d

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

desaturate_wheel_speeds: bool = True

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

forward_perspective: ForwardPerspectiveValue

The perspective to use when determining which direction is forward.

with_speeds(new_speeds: ChassisSpeeds) ApplyFieldSpeeds

Modifies the speeds parameter and returns itself.

The field-centric chassis speeds to apply to the drivetrain.

Parameters:

new_speeds (ChassisSpeeds) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_wheel_force_feedforwards_x(new_wheel_force_feedforwards_x: list[phoenix6.units.newton]) ApplyFieldSpeeds

Modifies the wheel_force_feedforwards_x parameter and returns itself.

Field-centric wheel force feedforwards to apply in the X direction, in newtons. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters:

new_wheel_force_feedforwards_x (list[newton]) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_wheel_force_feedforwards_y(new_wheel_force_feedforwards_y: list[phoenix6.units.newton]) ApplyFieldSpeeds

Modifies the wheel_force_feedforwards_y parameter and returns itself.

Field-centric wheel force feedforwards to apply in the Y direction, in newtons. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters:

new_wheel_force_feedforwards_y (list[newton]) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_center_of_rotation(new_center_of_rotation: Translation2d) ApplyFieldSpeeds

Modifies the center_of_rotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters:

new_center_of_rotation (Translation2d) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) ApplyFieldSpeeds

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) ApplyFieldSpeeds

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_desaturate_wheel_speeds(new_desaturate_wheel_speeds: bool) ApplyFieldSpeeds

Modifies the desaturate_wheel_speeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

Parameters:

new_desaturate_wheel_speeds (bool) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

with_forward_perspective(new_forward_perspective: ForwardPerspectiveValue) ApplyFieldSpeeds

Modifies the forward_perspective parameter and returns itself.

The perspective to use when determining which direction is forward.

Parameters:

new_forward_perspective (ForwardPerspectiveValue) – Parameter to modify

Returns:

this object

Return type:

ApplyFieldSpeeds

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

class phoenix6.swerve.requests.FieldCentricFacingAngle

Bases: SwerveRequest

Drives the swerve drivetrain in a field-centric manner, maintaining a specified heading angle to ensure the robot is facing the desired direction

When users use this request, they specify the direction the robot should travel oriented against the field, and the direction the robot should be facing.

An example scenario is that the robot is oriented to the east, the VelocityX is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees. In this scenario, the robot would drive northward at 5 m/s and turn clockwise to a target of 180 degrees.

This control request is especially useful for autonomous control, where the robot should be facing a changing direction throughout the motion.

velocity_x: phoenix6.units.meters_per_second = 0

The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

velocity_y: phoenix6.units.meters_per_second = 0

The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

target_direction: Rotation2d

The desired direction to face. 0 Degrees is defined as in the direction of the X axis. As a result, a TargetDirection of 90 degrees will point along the Y axis, or to the left.

target_rate_feedforward: phoenix6.units.radians_per_second = 0

The rotational rate feedforward to add to the output of the heading controller, in radians per second. When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.

deadband: phoenix6.units.meters_per_second = 0

The allowable deadband of the request, in m/s.

rotational_deadband: phoenix6.units.radians_per_second = 0

The rotational deadband of the request, in radians per second.

center_of_rotation: Translation2d

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType

The type of control request to use for the drive motor.

steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType

The type of control request to use for the drive motor.

desaturate_wheel_speeds: bool = True

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

forward_perspective: ForwardPerspectiveValue

The perspective to use when determining which direction is forward.

heading_controller: phoenix6.swerve.utility.phoenix_pid_controller.PhoenixPIDController

The PID controller used to maintain the desired heading. Users can specify the PID gains to change how aggressively to maintain heading.

This PID controller operates on heading radians and outputs a target rotational rate in radians per second. Note that continuous input should be enabled on the range [-pi, pi].

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

with_velocity_x(new_velocity_x: phoenix6.units.meters_per_second) FieldCentricFacingAngle

Modifies the velocity_x parameter and returns itself.

The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

Parameters:

new_velocity_x (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_velocity_y(new_velocity_y: phoenix6.units.meters_per_second) FieldCentricFacingAngle

Modifies the velocity_y parameter and returns itself.

The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

Parameters:

new_velocity_y (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_target_direction(new_target_direction: Rotation2d) FieldCentricFacingAngle

Modifies the target_direction parameter and returns itself.

The desired direction to face. 0 Degrees is defined as in the direction of the X axis. As a result, a TargetDirection of 90 degrees will point along the Y axis, or to the left.

Parameters:

new_target_direction (Rotation2d) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_target_rate_feedforward(new_target_rate_feedforward: phoenix6.units.radians_per_second) FieldCentricFacingAngle

Modifies the target_rate_feedforward parameter and returns itself.

The rotational rate feedforward to add to the output of the heading controller, in radians per second. When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.

Parameters:

new_target_rate_feedforward (radians_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_deadband(new_deadband: phoenix6.units.meters_per_second) FieldCentricFacingAngle

Modifies the deadband parameter and returns itself.

The allowable deadband of the request, in m/s.

Parameters:

new_deadband (meters_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_rotational_deadband(new_rotational_deadband: phoenix6.units.radians_per_second) FieldCentricFacingAngle

Modifies the rotational_deadband parameter and returns itself.

The rotational deadband of the request, in radians per second.

Parameters:

new_rotational_deadband (radians_per_second) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_center_of_rotation(new_center_of_rotation: Translation2d) FieldCentricFacingAngle

Modifies the center_of_rotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters:

new_center_of_rotation (Translation2d) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_drive_request_type(new_drive_request_type: phoenix6.swerve.swerve_module.SwerveModule.DriveRequestType) FieldCentricFacingAngle

Modifies the drive_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_drive_request_type (SwerveModule.DriveRequestType) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_steer_request_type(new_steer_request_type: phoenix6.swerve.swerve_module.SwerveModule.SteerRequestType) FieldCentricFacingAngle

Modifies the steer_request_type parameter and returns itself.

The type of control request to use for the drive motor.

Parameters:

new_steer_request_type (SwerveModule.SteerRequestType) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_desaturate_wheel_speeds(new_desaturate_wheel_speeds: bool) FieldCentricFacingAngle

Modifies the desaturate_wheel_speeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds.

Parameters:

new_desaturate_wheel_speeds (bool) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

with_forward_perspective(new_forward_perspective: ForwardPerspectiveValue) FieldCentricFacingAngle

Modifies the forward_perspective parameter and returns itself.

The perspective to use when determining which direction is forward.

Parameters:

new_forward_perspective (ForwardPerspectiveValue) – Parameter to modify

Returns:

this object

Return type:

FieldCentricFacingAngle

class phoenix6.swerve.requests.SysIdSwerveTranslation

Bases: SwerveRequest

SysId-specific SwerveRequest to characterize the translational characteristics of a swerve drivetrain.

volts_to_apply: phoenix6.units.volt = 0.0

Voltage to apply to drive wheels.

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

with_volts(volts: phoenix6.units.volt) SysIdSwerveTranslation

Sets the voltage to apply to the drive wheels.

Parameters:

volts (volt) – Voltage to apply

Returns:

this request

Return type:

SysIdSwerveTranslation

class phoenix6.swerve.requests.SysIdSwerveRotation

Bases: SwerveRequest

SysId-specific SwerveRequest to characterize the rotational characteristics of a swerve drivetrain. This is useful to characterize the heading controller for FieldCentricFacingAngle.

The RotationalRate of this swerve request should be logged. When importing the log to SysId, set the “voltage” to RotationalRate, “position” to the Pigeon 2 Yaw, and “velocity” to the Pigeon 2 AngularVelocityZWorld. Note that the position and velocity will both need to be scaled by pi/180.

Alternatively, the MotorVoltage of one of the drive motors can be loaded into the SysId “voltage” field, which can be useful when determining the MOI of the robot.

rotational_rate: phoenix6.units.radians_per_second = 0.0

The angular rate to rotate at, in radians per second.

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

with_rotational_rate(rotational_rate: phoenix6.units.radians_per_second) SysIdSwerveRotation

Sets the angular rate to rotate at, in radians per second.

Parameters:

rotational_rate (radians_per_second) – Angular rate to rotate at

Returns:

this request

Return type:

SysIdSwerveRotation

class phoenix6.swerve.requests.SysIdSwerveSteerGains

Bases: SwerveRequest

SysId-specific SwerveRequest to characterize the steer module characteristics of a swerve drivetrain.

volts_to_apply: phoenix6.units.volt = 0.0

Voltage to apply to steer wheels.

apply(parameters: phoenix6.swerve.swerve_drivetrain.SwerveControlParameters, modules_to_apply: list[phoenix6.swerve.swerve_module.SwerveModule]) phoenix6.status_code.StatusCode

Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

For native swerve requests, this API can be called from a non-native request’s apply to compose the two together.

Parameters:
  • parameters (SwerveControlParameters) – Parameters the control request needs to calculate the module state

  • modules_to_apply (list[SwerveModule]) – Modules to which the control request is applied

Returns:

Status code of sending the request

Return type:

StatusCode

with_volts(volts: phoenix6.units.volt) SysIdSwerveSteerGains

Sets the voltage to apply to the steer wheels.

Parameters:

volts (volt) – Voltage to apply

Returns:

this request

Return type:

SysIdSwerveSteerGains