SwerveDrive2Kinematics
- class wpimath.SwerveDrive2Kinematics(arg0: wpimath._wpimath.Translation2d, arg1: wpimath._wpimath.Translation2d)
Bases:
SwerveDrive2KinematicsBaseHelper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states (velocity 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 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: [moduleVelocities] = [moduleLocations] * [chassisVelocities] We take the Moore-Penrose pseudoinverse of [moduleLocations] and then multiply by [moduleVelocities] to get our chassis velocities.
Forward kinematics is also used for odometry – determining the position of the robot on the field using encoders and a gyro.
- static desaturateWheelVelocities(*args, **kwargs)
Overloaded function.
desaturateWheelVelocities(moduleVelocities: Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity], attainableMaxVelocity: wpimath.units.meters_per_second) -> Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]
Renormalizes the wheel velocities if any individual velocity is above the specified maximum.
Sometimes, after inverse kinematics, the requested velocity from one or more modules may be above the max attainable velocity for the driving motor on that module. To fix this issue, one can reduce all the wheel velocities to make sure that all requested module velocities are at-or-below the absolute threshold, while maintaining the ratio of velocities between modules.
Scaling down the module velocities rotates the direction of net motion in the opposite direction of rotational velocity, which makes discretizing the chassis velocities inaccurate because the discretization did not account for this translational skew.
- Parameters:
moduleVelocities – The array of module velocities.
attainableMaxVelocity – The absolute max velocity that a module can reach.
- Returns:
The array of desaturated module velocities.
desaturateWheelVelocities(moduleVelocities: Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity], desiredChassisVelocity: wpimath._wpimath.ChassisVelocities, attainableMaxModuleVelocity: wpimath.units.meters_per_second, attainableMaxRobotTranslationVelocity: wpimath.units.meters_per_second, attainableMaxRobotRotationVelocity: wpimath.units.radians_per_second) -> Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]
Renormalizes the wheel velocities if any individual velocity is above the specified maximum, as well as getting rid of joystick saturation at edges of joystick.
Sometimes, after inverse kinematics, the requested velocity from one or more modules may be above the max attainable velocity for the driving motor on that module. To fix this issue, one can reduce all the wheel velocities to make sure that all requested module velocities are at-or-below the absolute threshold, while maintaining the ratio of velocities between modules.
Scaling down the module velocities rotates the direction of net motion in the opposite direction of rotational velocity, which makes discretizing the chassis velocities inaccurate because the discretization did not account for this translational skew.
- Parameters:
moduleVelocities – The array of module velocities.
desiredChassisVelocity – The desired velocity of the robot
attainableMaxModuleVelocity – The absolute max velocity a module can reach
attainableMaxRobotTranslationVelocity – The absolute max velocity the robot can reach while translating
attainableMaxRobotRotationVelocity – The absolute max velocity the robot can reach while rotating
- Returns:
The array of desaturated module velocities
- getModules() Tuple[wpimath._wpimath.Translation2d, wpimath._wpimath.Translation2d]
- interpolate(start: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition], end: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition], t: SupportsFloat | SupportsIndex) Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition]
- resetHeadings(moduleHeadings: Tuple[wpimath._wpimath.Rotation2d, wpimath._wpimath.Rotation2d]) None
Reset the internal swerve module headings.
- Parameters:
moduleHeadings – The swerve module headings. The order of the module headings should be same as passed into the constructor of this class.
- toChassisAccelerations(moduleAccelerations: Tuple[wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration]) wpimath._wpimath.ChassisAccelerations
Performs forward kinematics to return the resulting chassis accelerations from the given module accelerations. This method is often used for dynamics calculations – determining the robot’s acceleration on the field using data from the real-world acceleration of each module on the robot.
- Parameters:
moduleAccelerations – The accelerations of the modules as measured from respective encoders and gyros. The order of the swerve module accelerations should be same as passed into the constructor of this class.
- Returns:
The resulting chassis accelerations.
- toChassisVelocities(moduleVelocities: Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]) wpimath._wpimath.ChassisVelocities
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 velocity and angle of each module on the robot.
- Parameters:
moduleVelocities – The state of the modules as an wpi::util::array of type SwerveModuleVelocity, NumModules long 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 velocity.
- toSwerveModuleAccelerations(chassisAccelerations: wpimath._wpimath.ChassisAccelerations, angularVelocity: wpimath.units.radians_per_second = 0.0, centerOfRotation: wpimath._wpimath.Translation2d = Translation2d(x=0.000000, y=0.000000)) Tuple[wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration]
Performs inverse kinematics to return the module accelerations from a desired chassis acceleration. This method is often used for dynamics calculations – converting desired robot accelerations into individual module accelerations.
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.
- Parameters:
chassisAccelerations – The desired chassis accelerations.
angularVelocity – The desired robot angular velocity.
centerOfRotation – The center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis acceleration that only has a dtheta component, the robot will rotate around that corner.
- Returns:
An array containing the module accelerations.
- toSwerveModuleVelocities(chassisVelocities: wpimath._wpimath.ChassisVelocities, centerOfRotation: wpimath._wpimath.Translation2d = Translation2d(x=0.000000, y=0.000000)) Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]
Performs inverse kinematics to return the module states from a desired chassis velocity. This method is often used to convert joystick values into module velocities 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.
- Parameters:
chassisVelocities – The desired chassis velocity.
centerOfRotation – The center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis velocity 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 velocities to go above the attainable max velocity. Use the
desaturateWheelVelocities()function to rectify this issue. In addition, you can use Python unpacking syntax to directly assign the module states to variables:fl, fr, bl, br = kinematics.toSwerveModuleVelocities(chassisVelocities)
- toTwist2d(*args, **kwargs)
Overloaded function.
toTwist2d(self: wpimath._wpimath.SwerveDrive2Kinematics, moduleDeltas: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition]) -> wpimath._wpimath.Twist2d
Performs forward kinematics to return the resulting Twist2d from the given module position deltas. This method is often used for odometry – determining the robot’s position on the field using data from the real-world position delta and angle of each module on the robot.
- Parameters:
moduleDeltas – The 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.
toTwist2d(self: wpimath._wpimath.SwerveDrive2Kinematics, start: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition], end: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition]) -> wpimath._wpimath.Twist2d
- toWheelAccelerations(chassisAccelerations: wpimath._wpimath.ChassisAccelerations) Tuple[wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration]
Performs inverse kinematics to return the module accelerations from a desired chassis acceleration. This method is often used for dynamics calculations – converting desired robot accelerations into individual module accelerations.
- Parameters:
chassisAccelerations – The desired chassis accelerations.
- Returns:
An array containing the module accelerations.
- toWheelVelocities(chassisVelocities: wpimath._wpimath.ChassisVelocities) Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]