Class ChoreoTrajectoryState

java.lang.Object
com.choreo.lib.ChoreoTrajectoryState
All Implemented Interfaces:
Interpolatable<ChoreoTrajectoryState>

public class ChoreoTrajectoryState extends Object implements Interpolatable<ChoreoTrajectoryState>
A single robot state in a ChoreoTrajectory.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final double
    The angular velocity of the state in rad/s.
    final double
    The heading of the state in radians, with 0 being in the +X direction.
    final double[]
    The force on each swerve module in the X direction in Newtons.
    final double[]
    The force on each swerve module in the Y direction in Newtons Module forces appear in the following order: [FL, FR, BL, BR].
    final double
    The timestamp of this state, relative to the beginning of the trajectory.
    final double
    The velocity of the state in the X direction in m/s.
    final double
    The velocity of the state in the Y direction in m/s.
    final double
    The X position of the state in meters.
    final double
    The Y position of the state in meters.
  • Constructor Summary

    Constructors
    Constructor
    Description
    ChoreoTrajectoryState(double timestamp, double x, double y, double heading, double velocityX, double velocityY, double angularVelocity, double[] moduleForcesX, double[] moduleForcesY)
    Constructs a ChoreoTrajectoryState with the specified parameters.
  • Method Summary

    Modifier and Type
    Method
    Description
    Returns this state, mirrored across the field midline.
    Returns the field-relative chassis speeds of this state.
    Returns the pose at this state.
    interpolate(ChoreoTrajectoryState endValue, double t)
    Interpolate between this state and the provided state.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • timestamp

      public final double timestamp
      The timestamp of this state, relative to the beginning of the trajectory.
    • x

      public final double x
      The X position of the state in meters.
    • y

      public final double y
      The Y position of the state in meters.
    • heading

      public final double heading
      The heading of the state in radians, with 0 being in the +X direction.
    • velocityX

      public final double velocityX
      The velocity of the state in the X direction in m/s.
    • velocityY

      public final double velocityY
      The velocity of the state in the Y direction in m/s.
    • angularVelocity

      public final double angularVelocity
      The angular velocity of the state in rad/s.
    • moduleForcesX

      public final double[] moduleForcesX
      The force on each swerve module in the X direction in Newtons. Module forces appear in the following order: [FL, FR, BL, BR].
    • moduleForcesY

      public final double[] moduleForcesY
      The force on each swerve module in the Y direction in Newtons Module forces appear in the following order: [FL, FR, BL, BR].
  • Constructor Details

    • ChoreoTrajectoryState

      public ChoreoTrajectoryState(double timestamp, double x, double y, double heading, double velocityX, double velocityY, double angularVelocity, double[] moduleForcesX, double[] moduleForcesY)
      Constructs a ChoreoTrajectoryState with the specified parameters.
      Parameters:
      timestamp - The timestamp of this state, relative to the beginning of the trajectory.
      x - The X position of the state in meters.
      y - The Y position of the state in meters.
      heading - The heading of the state in radians, with 0 being in the +X direction.
      velocityX - The velocity of the state in the X direction in m/s.
      velocityY - The velocity of the state in the Y direction in m/s.
      angularVelocity - The angular velocity of the state in rad/s.
      moduleForcesX - The force on each swerve module in the X direction in Newtons.
      moduleForcesY - The force on each swerve module in the Y direction in Netwons.
  • Method Details

    • getPose

      public Pose2d getPose()
      Returns the pose at this state.
      Returns:
      the pose at this state.
    • getChassisSpeeds

      public ChassisSpeeds getChassisSpeeds()
      Returns the field-relative chassis speeds of this state.
      Returns:
      the field-relative chassis speeds of this state.
    • interpolate

      public ChoreoTrajectoryState interpolate(ChoreoTrajectoryState endValue, double t)
      Interpolate between this state and the provided state.
      Specified by:
      interpolate in interface Interpolatable<ChoreoTrajectoryState>
      Parameters:
      endValue - The next state. It should have a timestamp after this state.
      t - The timestamp of the interpolated state. It should be between this state and endValue.
      Returns:
      the interpolated state.
    • flipped

      public ChoreoTrajectoryState flipped()
      Returns this state, mirrored across the field midline.
      Returns:
      this state, mirrored across the field midline.