Package edu.wpi.first.wpilibj.kinematics
Class DifferentialDriveWheelSpeeds
- java.lang.Object
-
- edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds
-
public class DifferentialDriveWheelSpeeds extends Object
Represents the wheel speeds for a differential drive drivetrain.
-
-
Field Summary
Fields Modifier and Type Field Description doubleleftMetersPerSecondSpeed of the left side of the robot.doublerightMetersPerSecondSpeed 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
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidnormalize(double attainableMaxSpeedMetersPerSecond)Normalizes the wheel speeds using some max attainable speed.StringtoString()
-
-
-
Constructor Detail
-
DifferentialDriveWheelSpeeds
public DifferentialDriveWheelSpeeds()
Constructs a DifferentialDriveWheelSpeeds with zeros for left and right speeds.
-
DifferentialDriveWheelSpeeds
public DifferentialDriveWheelSpeeds(double leftMetersPerSecond, double rightMetersPerSecond)Constructs a DifferentialDriveWheelSpeeds.- Parameters:
leftMetersPerSecond- The left speed.rightMetersPerSecond- The right speed.
-
-
Method Detail
-
normalize
public void normalize(double attainableMaxSpeedMetersPerSecond)
Normalizes the wheel speeds using some max attainable speed. Sometimes, after inverse kinematics, the requested speed from a/several modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can "normalize" all the wheel speeds to make sure that all requested module speeds are below the absolute threshold, while maintaining the ratio of speeds between modules.- Parameters:
attainableMaxSpeedMetersPerSecond- The absolute max speed that a wheel can reach.
-
-