Class ChassisAccelerations

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

Represents robot chassis accelerations.

A strictly non-holonomic drivetrain, such as a differential drive, should never have an ay component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum will often have all three components.

  • Field Details

    • ax

      public double ax
      Acceleration along the x-axis in meters per second squared. (Fwd is +)
    • ay

      public double ay
      Acceleration along the y-axis in meters per second squared. (Left is +)
    • alpha

      public double alpha
      Angular acceleration of the robot frame in radians per second squared. (CCW is +)
    • struct

      public static final ChassisAccelerationsStruct struct
      ChassisAccelerations struct for serialization.
    • proto

      public static final ChassisAccelerationsProto proto
      ChassisAccelerations proto for serialization.
  • Constructor Details

    • ChassisAccelerations

      Constructs a ChassisAccelerations with zeros for ax, ay, and omega.
    • ChassisAccelerations

      public ChassisAccelerations(double ax, double ay, double alpha)
      Constructs a ChassisAccelerations object.
      Parameters:
      ax - Forward acceleration in meters per second squared.
      ay - Sideways acceleration in meters per second squared.
      alpha - Angular acceleration in radians per second squared.
    • ChassisAccelerations

      Constructs a ChassisAccelerations object.
      Parameters:
      ax - Forward acceleration.
      ay - Sideways acceleration.
      alpha - Angular acceleration.
  • Method Details

    • toRobotRelative

      Converts this field-relative set of accelerations into a robot-relative ChassisAccelerations object.
      Parameters:
      robotAngle - The angle of the robot as measured by a gyroscope. The robot's angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.
      Returns:
      ChassisAccelerations object representing the accelerations in the robot's frame of reference.
    • toFieldRelative

      Converts this robot-relative set of accelerations into a field-relative ChassisAccelerations object.
      Parameters:
      robotAngle - The angle of the robot as measured by a gyroscope. The robot's angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.
      Returns:
      ChassisAccelerations object representing the accelerations in the field's frame of reference.
    • plus

      Adds two ChassisAccelerations and returns the sum.

      For example, ChassisAccelerations{1.0, 0.5, 0.75} + ChassisAccelerations{2.0, 1.5, 0.25} = ChassisAccelerations{3.0, 2.0, 1.0}

      Parameters:
      other - The ChassisAccelerations to add.
      Returns:
      The sum of the ChassisAccelerations.
    • minus

      Subtracts the other ChassisAccelerations from the current ChassisAccelerations and returns the difference.

      For example, ChassisAccelerations{5.0, 4.0, 2.0} - ChassisAccelerations{1.0, 2.0, 1.0} = ChassisAccelerations{4.0, 2.0, 1.0}

      Parameters:
      other - The ChassisAccelerations to subtract.
      Returns:
      The difference between the two ChassisAccelerations.
    • unaryMinus

      Returns the inverse of the current ChassisAccelerations. This is equivalent to negating all components of the ChassisAccelerations.
      Returns:
      The inverse of the current ChassisAccelerations.
    • times

      public ChassisAccelerations times(double scalar)
      Multiplies the ChassisAccelerations by a scalar and returns the new ChassisAccelerations.

      For example, ChassisAccelerations{2.0, 2.5, 1.0} * 2 = ChassisAccelerations{4.0, 5.0, 1.0}

      Parameters:
      scalar - The scalar to multiply by.
      Returns:
      The scaled ChassisAccelerations.
    • div

      public ChassisAccelerations div(double scalar)
      Divides the ChassisAccelerations by a scalar and returns the new ChassisAccelerations.

      For example, ChassisAccelerations{2.0, 2.5, 1.0} / 2 = ChassisAccelerations{1.0, 1.25, 0.5}

      Parameters:
      scalar - The scalar to divide by.
      Returns:
      The scaled ChassisAccelerations.
    • interpolate

      Description copied from interface: Interpolatable
      Return the interpolated value. This object is assumed to be the starting position, or lower bound.
      Specified by:
      interpolate in interface Interpolatable<ChassisAccelerations>
      Parameters:
      endValue - The upper bound, or end.
      t - How far between the lower and upper bound we are. This should be bounded in [0, 1].
      Returns:
      The interpolated value.
    • hashCode

      public final int hashCode()
      Overrides:
      hashCode in class Object
    • equals

      public boolean equals(Object o)
      Overrides:
      equals in class Object
    • toString

      public String toString()
      Overrides:
      toString in class Object