Package edu.wpi.first.wpilibj.kinematics
Class MecanumDriveWheelSpeeds
- java.lang.Object
-
- edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds
-
public class MecanumDriveWheelSpeeds extends Object
-
-
Field Summary
Fields Modifier and Type Field Description doublefrontLeftMetersPerSecondSpeed of the front left wheel.doublefrontRightMetersPerSecondSpeed of the front right wheel.doublerearLeftMetersPerSecondSpeed of the rear left wheel.doublerearRightMetersPerSecondSpeed of the rear right wheel.
-
Constructor Summary
Constructors Constructor Description MecanumDriveWheelSpeeds()Constructs a MecanumDriveWheelSpeeds with zeros for all member fields.MecanumDriveWheelSpeeds(double frontLeftMetersPerSecond, double frontRightMetersPerSecond, double rearLeftMetersPerSecond, double rearRightMetersPerSecond)Constructs a MecanumDriveWheelSpeeds.
-
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()
-
-
-
Field Detail
-
frontLeftMetersPerSecond
public double frontLeftMetersPerSecond
Speed of the front left wheel.
-
frontRightMetersPerSecond
public double frontRightMetersPerSecond
Speed of the front right wheel.
-
rearLeftMetersPerSecond
public double rearLeftMetersPerSecond
Speed of the rear left wheel.
-
rearRightMetersPerSecond
public double rearRightMetersPerSecond
Speed of the rear right wheel.
-
-
Constructor Detail
-
MecanumDriveWheelSpeeds
public MecanumDriveWheelSpeeds()
Constructs a MecanumDriveWheelSpeeds with zeros for all member fields.
-
MecanumDriveWheelSpeeds
public MecanumDriveWheelSpeeds(double frontLeftMetersPerSecond, double frontRightMetersPerSecond, double rearLeftMetersPerSecond, double rearRightMetersPerSecond)Constructs a MecanumDriveWheelSpeeds.- Parameters:
frontLeftMetersPerSecond- Speed of the front left wheel.frontRightMetersPerSecond- Speed of the front right wheel.rearLeftMetersPerSecond- Speed of the rear left wheel.rearRightMetersPerSecond- Speed of the rear right wheel.
-
-
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.
-
-