Package edu.wpi.first.math.kinematics
Class DifferentialDriveWheelSpeeds
java.lang.Object
edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds
public class DifferentialDriveWheelSpeeds extends Object
Represents the wheel speeds for a differential drive drivetrain.
-
Field Summary
Fields Modifier and Type Field Description double
leftMetersPerSecond
Speed of the left side of the robot.double
rightMetersPerSecond
Speed of the right side of the robot. -
Constructor Summary
Constructors Constructor Description DifferentialDriveWheelSpeeds()
Constructs a DifferentialDriveWheelSpeeds with zeros for left and right speeds.DifferentialDriveWheelSpeeds(double leftMetersPerSecond, double rightMetersPerSecond)
Constructs a DifferentialDriveWheelSpeeds. -
Method Summary
Modifier and Type Method Description void
desaturate(double attainableMaxSpeedMetersPerSecond)
Renormalizes the wheel speeds if any either side is above the specified maximum.String
toString()
-
Field Details
-
leftMetersPerSecond
Speed of the left side of the robot. -
rightMetersPerSecond
Speed of the right side of the robot.
-
-
Constructor Details
-
DifferentialDriveWheelSpeeds
public DifferentialDriveWheelSpeeds()Constructs a DifferentialDriveWheelSpeeds with zeros for left and right speeds. -
DifferentialDriveWheelSpeeds
Constructs a DifferentialDriveWheelSpeeds.- Parameters:
leftMetersPerSecond
- The left speed.rightMetersPerSecond
- The right speed.
-
-
Method Details
-
desaturate
Renormalizes the wheel speeds if any either side is above the specified maximum.Sometimes, after inverse kinematics, the requested speed from one or more wheels may be above the max attainable speed for the driving motor on that wheel. 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 wheels.
- Parameters:
attainableMaxSpeedMetersPerSecond
- The absolute max speed that a wheel can reach.
-
toString
-