Class MecanumDriveWheelVelocities

java.lang.Object
org.wpilib.math.kinematics.MecanumDriveWheelVelocities
All Implemented Interfaces:
Interpolatable<MecanumDriveWheelVelocities>, ProtobufSerializable, StructSerializable, WPISerializable

Represents the wheel velocities for a mecanum drive drivetrain.
  • Field Details

    • frontLeft

      public double frontLeft
      Velocity of the front left wheel in meters per second.
    • frontRight

      public double frontRight
      Velocity of the front right wheel in meters per second.
    • rearLeft

      public double rearLeft
      Velocity of the rear left wheel in meters per second.
    • rearRight

      public double rearRight
      Velocity of the rear right wheel in meters per second.
    • proto

      MecanumDriveWheelVelocities protobuf for serialization.
    • struct

      MecanumDriveWheelVelocities struct for serialization.
  • Constructor Details

    • 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

      public MecanumDriveWheelVelocities desaturate(double attainableMaxVelocity)
      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

      public MecanumDriveWheelVelocities desaturate(LinearVelocity attainableMaxVelocity)
      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

      public MecanumDriveWheelVelocities times(double scalar)
      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

      public MecanumDriveWheelVelocities div(double scalar)
      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:
      interpolate in interface Interpolatable<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

      public String toString()
      Overrides:
      toString in class Object