Class MecanumDriveWheelVelocities
- All Implemented Interfaces:
Interpolatable<MecanumDriveWheelVelocities>, ProtobufSerializable, StructSerializable, WPISerializable
-
Field Summary
FieldsModifier and TypeFieldDescriptiondoubleVelocity of the front left wheel in meters per second.doubleVelocity of the front right wheel in meters per second.static final MecanumDriveWheelVelocitiesProtoMecanumDriveWheelVelocities protobuf for serialization.doubleVelocity of the rear left wheel in meters per second.doubleVelocity of the rear right wheel in meters per second.static final MecanumDriveWheelVelocitiesStructMecanumDriveWheelVelocities struct for serialization. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs a MecanumDriveWheelVelocities with zeros for all member fields.MecanumDriveWheelVelocities(double frontLeft, double frontRight, double rearLeft, double rearRight) Constructs a MecanumDriveWheelVelocities.MecanumDriveWheelVelocities(LinearVelocity frontLeft, LinearVelocity frontRight, LinearVelocity rearLeft, LinearVelocity rearRight) Constructs a MecanumDriveWheelVelocities. -
Method Summary
Modifier and TypeMethodDescriptiondesaturate(double attainableMaxVelocity) Renormalizes the wheel velocities if any individual velocity is above the specified maximum.desaturate(LinearVelocity attainableMaxVelocity) Renormalizes the wheel velocities if any individual velocity is above the specified maximum.div(double scalar) Divides the MecanumDriveWheelVelocities by a scalar and returns the new MecanumDriveWheelVelocities.interpolate(MecanumDriveWheelVelocities endValue, double t) Returns the linear interpolation of this MecanumDriveWheelVelocities and another.minus(MecanumDriveWheelVelocities other) Subtracts the other MecanumDriveWheelVelocities from the current MecanumDriveWheelVelocities and returns the difference.plus(MecanumDriveWheelVelocities other) Adds two MecanumDriveWheelVelocities and returns the sum.times(double scalar) Multiplies the MecanumDriveWheelVelocities by a scalar and returns the new MecanumDriveWheelVelocities.toString()Returns the inverse of the current MecanumDriveWheelVelocities.
-
Field Details
-
frontLeft
Velocity of the front left wheel in meters per second. -
frontRight
Velocity of the front right wheel in meters per second. -
rearLeft
Velocity of the rear left wheel in meters per second. -
rearRight
Velocity of the rear right wheel in meters per second. -
proto
MecanumDriveWheelVelocities protobuf for serialization. -
struct
MecanumDriveWheelVelocities struct for serialization.
-
-
Constructor Details
-
MecanumDriveWheelVelocities
public MecanumDriveWheelVelocities()Constructs a MecanumDriveWheelVelocities with zeros for all member fields. -
MecanumDriveWheelVelocities
public MecanumDriveWheelVelocities(double frontLeft, double frontRight, double rearLeft, double rearRight) Constructs a MecanumDriveWheelVelocities.- Parameters:
frontLeft- Velocity of the front left wheel in meters per second.frontRight- Velocity of the front right wheel in meters per second.rearLeft- Velocity of the rear left wheel in meters per second.rearRight- Velocity of the rear right wheel in meters per second.
-
MecanumDriveWheelVelocities
public MecanumDriveWheelVelocities(LinearVelocity frontLeft, LinearVelocity frontRight, LinearVelocity rearLeft, LinearVelocity rearRight) Constructs a MecanumDriveWheelVelocities.- Parameters:
frontLeft- Velocity of the front left wheel in meters per second.frontRight- Velocity of the front right wheel in meters per second.rearLeft- Velocity of the rear left wheel in meters per second.rearRight- Velocity of the rear right wheel in meters per second.
-
-
Method Details
-
desaturate
Renormalizes the wheel velocities if any individual velocity is above the specified maximum.Sometimes, after inverse kinematics, the requested velocity from one or more wheels may be above the max attainable velocity for the driving motor on that wheel. 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 wheels.
- Parameters:
attainableMaxVelocity- The absolute max velocity in meters per second that a wheel can reach.- Returns:
- Desaturated MecanumDriveWheelVelocities.
-
desaturate
Renormalizes the wheel velocities if any individual velocity is above the specified maximum.Sometimes, after inverse kinematics, the requested velocity from one or more wheels may be above the max attainable velocity for the driving motor on that wheel. 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 wheels.
- Parameters:
attainableMaxVelocity- The absolute max velocity that a wheel can reach.- Returns:
- Desaturated MecanumDriveWheelVelocities.
-
plus
Adds two MecanumDriveWheelVelocities and returns the sum.For example, MecanumDriveWheelVelocities{1.0, 0.5, 2.0, 1.5} + MecanumDriveWheelVelocities{2.0, 1.5, 0.5, 1.0} = MecanumDriveWheelVelocities{3.0, 2.0, 2.5, 2.5}
- Parameters:
other- The MecanumDriveWheelVelocities to add.- Returns:
- The sum of the MecanumDriveWheelVelocities.
-
minus
Subtracts the other MecanumDriveWheelVelocities from the current MecanumDriveWheelVelocities and returns the difference.For example, MecanumDriveWheelVelocities{5.0, 4.0, 6.0, 2.5} - MecanumDriveWheelVelocities{1.0, 2.0, 3.0, 0.5} = MecanumDriveWheelVelocities{4.0, 2.0, 3.0, 2.0}
- Parameters:
other- The MecanumDriveWheelVelocities to subtract.- Returns:
- The difference between the two MecanumDriveWheelVelocities.
-
unaryMinus
Returns the inverse of the current MecanumDriveWheelVelocities. This is equivalent to negating all components of the MecanumDriveWheelVelocities.- Returns:
- The inverse of the current MecanumDriveWheelVelocities.
-
times
Multiplies the MecanumDriveWheelVelocities by a scalar and returns the new MecanumDriveWheelVelocities.For example, MecanumDriveWheelVelocities{2.0, 2.5, 3.0, 3.5} * 2 = MecanumDriveWheelVelocities{4.0, 5.0, 6.0, 7.0}
- Parameters:
scalar- The scalar to multiply by.- Returns:
- The scaled MecanumDriveWheelVelocities.
-
div
Divides the MecanumDriveWheelVelocities by a scalar and returns the new MecanumDriveWheelVelocities.For example, MecanumDriveWheelVelocities{2.0, 2.5, 1.5, 1.0} / 2 = MecanumDriveWheelVelocities{1.0, 1.25, 0.75, 0.5}
- Parameters:
scalar- The scalar to divide by.- Returns:
- The scaled MecanumDriveWheelVelocities.
-
interpolate
Returns the linear interpolation of this MecanumDriveWheelVelocities and another.- Specified by:
interpolatein interfaceInterpolatable<MecanumDriveWheelVelocities>- Parameters:
endValue- The end value for the interpolation.t- How far between the two values to interpolate. This is clamped to [0, 1].- Returns:
- The interpolated value.
-
toString
-