Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.kinematics.SwerveDriveKinematics Class Reference
Inheritance diagram for edu.wpi.first.math.kinematics.SwerveDriveKinematics:
edu.wpi.first.math.kinematics.Kinematics< SwerveDriveKinematics.SwerveDriveWheelStates, SwerveDriveWheelPositions >

Public Member Functions

 SwerveDriveKinematics (Translation2d... moduleTranslationsMeters)
 
void resetHeadings (Rotation2d... moduleHeadings)
 
SwerveModuleState[] toSwerveModuleStates (ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters)
 
SwerveModuleState[] toSwerveModuleStates (ChassisSpeeds chassisSpeeds)
 
ChassisSpeeds toChassisSpeeds (SwerveModuleState... moduleStates)
 
Twist2d toTwist2d (SwerveModulePosition... moduleDeltas)
 
- Public Member Functions inherited from edu.wpi.first.math.kinematics.Kinematics< SwerveDriveKinematics.SwerveDriveWheelStates, SwerveDriveWheelPositions >
ChassisSpeeds toChassisSpeeds (S wheelSpeeds)
 
toWheelSpeeds (ChassisSpeeds chassisSpeeds)
 
Twist2d toTwist2d (P start, P end)
 

Static Public Member Functions

static void desaturateWheelSpeeds (SwerveModuleState[] moduleStates, double attainableMaxSpeedMetersPerSecond)
 
static void desaturateWheelSpeeds (SwerveModuleState[] moduleStates, Measure< Velocity< Distance > > attainableMaxSpeed)
 
static void desaturateWheelSpeeds (SwerveModuleState[] moduleStates, ChassisSpeeds desiredChassisSpeed, double attainableMaxModuleSpeedMetersPerSecond, double attainableMaxTranslationalSpeedMetersPerSecond, double attainableMaxRotationalVelocityRadiansPerSecond)
 
static void desaturateWheelSpeeds (SwerveModuleState[] moduleStates, ChassisSpeeds desiredChassisSpeed, Measure< Velocity< Distance > > attainableMaxModuleSpeed, Measure< Velocity< Distance > > attainableMaxTranslationalSpeed, Measure< Velocity< Angle > > attainableMaxRotationalVelocity)
 

Detailed Description

Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states (speed and angle).

The inverse kinematics (converting from a desired chassis velocity to individual module states) uses the relative locations of the modules with respect to the center of rotation. The center of rotation for inverse kinematics is also variable. This means that you can set your center of rotation in a corner of the robot to perform special evasion maneuvers.

Forward kinematics (converting an array of module states into the overall chassis motion) is performs the exact opposite of what inverse kinematics does. Since this is an overdetermined system (more equations than variables), we use a least-squares approximation.

The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds] We take the Moore-Penrose pseudoinverse of [moduleLocations] and then multiply by [moduleStates] to get our chassis speeds.

Forward kinematics is also used for odometry – determining the position of the robot on the field using encoders and a gyro.

Constructor & Destructor Documentation

◆ SwerveDriveKinematics()

edu.wpi.first.math.kinematics.SwerveDriveKinematics.SwerveDriveKinematics ( Translation2d... moduleTranslationsMeters)

Constructs a swerve drive kinematics object. This takes in a variable number of module locations as Translation2d objects. The order in which you pass in the module locations is the same order that you will receive the module states when performing inverse kinematics. It is also expected that you pass in the module states in the same order when calling the forward kinematics methods.

Parameters
moduleTranslationsMetersThe locations of the modules relative to the physical center of the robot.

Member Function Documentation

◆ desaturateWheelSpeeds() [1/4]

static void edu.wpi.first.math.kinematics.SwerveDriveKinematics.desaturateWheelSpeeds ( SwerveModuleState[] moduleStates,
ChassisSpeeds desiredChassisSpeed,
double attainableMaxModuleSpeedMetersPerSecond,
double attainableMaxTranslationalSpeedMetersPerSecond,
double attainableMaxRotationalVelocityRadiansPerSecond )
static

Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well as getting rid of joystick saturation at edges of joystick.

Sometimes, after inverse kinematics, the requested speed from one or more modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between modules.

Parameters
moduleStatesReference to array of module states. The array will be mutated with the normalized speeds!
desiredChassisSpeedThe desired speed of the robot
attainableMaxModuleSpeedMetersPerSecondThe absolute max speed that a module can reach
attainableMaxTranslationalSpeedMetersPerSecondThe absolute max speed that your robot can reach while translating
attainableMaxRotationalVelocityRadiansPerSecondThe absolute max speed the robot can reach while rotating

◆ desaturateWheelSpeeds() [2/4]

static void edu.wpi.first.math.kinematics.SwerveDriveKinematics.desaturateWheelSpeeds ( SwerveModuleState[] moduleStates,
ChassisSpeeds desiredChassisSpeed,
Measure< Velocity< Distance > > attainableMaxModuleSpeed,
Measure< Velocity< Distance > > attainableMaxTranslationalSpeed,
Measure< Velocity< Angle > > attainableMaxRotationalVelocity )
static

Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well as getting rid of joystick saturation at edges of joystick.

Sometimes, after inverse kinematics, the requested speed from one or more modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between modules.

Parameters
moduleStatesReference to array of module states. The array will be mutated with the normalized speeds!
desiredChassisSpeedThe desired speed of the robot
attainableMaxModuleSpeedThe absolute max speed that a module can reach
attainableMaxTranslationalSpeedThe absolute max speed that your robot can reach while translating
attainableMaxRotationalVelocityThe absolute max speed the robot can reach while rotating

◆ desaturateWheelSpeeds() [3/4]

static void edu.wpi.first.math.kinematics.SwerveDriveKinematics.desaturateWheelSpeeds ( SwerveModuleState[] moduleStates,
double attainableMaxSpeedMetersPerSecond )
static

Renormalizes the wheel speeds if any individual speed is above the specified maximum.

Sometimes, after inverse kinematics, the requested speed from one or more modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between modules.

Parameters
moduleStatesReference to array of module states. The array will be mutated with the normalized speeds!
attainableMaxSpeedMetersPerSecondThe absolute max speed that a module can reach.

◆ desaturateWheelSpeeds() [4/4]

static void edu.wpi.first.math.kinematics.SwerveDriveKinematics.desaturateWheelSpeeds ( SwerveModuleState[] moduleStates,
Measure< Velocity< Distance > > attainableMaxSpeed )
static

Renormalizes the wheel speeds if any individual speed is above the specified maximum.

Sometimes, after inverse kinematics, the requested speed from one or more modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between modules.

Parameters
moduleStatesReference to array of module states. The array will be mutated with the normalized speeds!
attainableMaxSpeedThe absolute max speed that a module can reach.

◆ resetHeadings()

void edu.wpi.first.math.kinematics.SwerveDriveKinematics.resetHeadings ( Rotation2d... moduleHeadings)

Reset the internal swerve module headings.

Parameters
moduleHeadingsThe swerve module headings. The order of the module headings should be same as passed into the constructor of this class.

◆ toChassisSpeeds()

ChassisSpeeds edu.wpi.first.math.kinematics.SwerveDriveKinematics.toChassisSpeeds ( SwerveModuleState... moduleStates)

Performs forward kinematics to return the resulting chassis state from the given module states. This method is often used for odometry – determining the robot's position on the field using data from the real-world speed and angle of each module on the robot.

Parameters
moduleStatesThe state of the modules (as a SwerveModuleState type) as measured from respective encoders and gyros. The order of the swerve module states should be same as passed into the constructor of this class.
Returns
The resulting chassis speed.

◆ toSwerveModuleStates() [1/2]

SwerveModuleState[] edu.wpi.first.math.kinematics.SwerveDriveKinematics.toSwerveModuleStates ( ChassisSpeeds chassisSpeeds)

Performs inverse kinematics. See toSwerveModuleStates(ChassisSpeeds, Translation2d) toSwerveModuleStates for more information.

Parameters
chassisSpeedsThe desired chassis speed.
Returns
An array containing the module states.

◆ toSwerveModuleStates() [2/2]

SwerveModuleState[] edu.wpi.first.math.kinematics.SwerveDriveKinematics.toSwerveModuleStates ( ChassisSpeeds chassisSpeeds,
Translation2d centerOfRotationMeters )

Performs inverse kinematics to return the module states from a desired chassis velocity. This method is often used to convert joystick values into module speeds and angles.

This function also supports variable centers of rotation. During normal operations, the center of rotation is usually the same as the physical center of the robot; therefore, the argument is defaulted to that use case. However, if you wish to change the center of rotation for evasive maneuvers, vision alignment, or for any other use case, you can do so.

In the case that the desired chassis speeds are zero (i.e. the robot will be stationary), the previously calculated module angle will be maintained.

Parameters
chassisSpeedsThe desired chassis speed.
centerOfRotationMetersThe center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis speed that only has a dtheta component, the robot will rotate around that corner.
Returns
An array containing the module states. Use caution because these module states are not normalized. Sometimes, a user input may cause one of the module speeds to go above the attainable max velocity. Use the DesaturateWheelSpeeds function to rectify this issue.

◆ toTwist2d()

Twist2d edu.wpi.first.math.kinematics.SwerveDriveKinematics.toTwist2d ( SwerveModulePosition... moduleDeltas)

Performs forward kinematics to return the resulting chassis state from the given module states. This method is often used for odometry – determining the robot's position on the field using data from the real-world speed and angle of each module on the robot.

Parameters
moduleDeltasThe latest change in position of the modules (as a SwerveModulePosition type) as measured from respective encoders and gyros. The order of the swerve module states should be same as passed into the constructor of this class.
Returns
The resulting Twist2d.

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