Package com.choreo.lib
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 doubleangularVelocityThe angular velocity of the state in rad/s.doubleheadingThe heading of the state in radians, with 0 being in the +X direction.doubletimestampThe timestamp of this state, relative to the beginning of the trajectory.doublevelocityXThe velocity of the state in the X direction in m/s.doublevelocityYThe velocity of the state in the X direction in m/s.doublexThe X position of the state in meters.doubleyThe 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)Constructs a ChoreoTrajectoryState with the specified parameters.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description double[]asArray()Returns this state as a double array: {timestamp, x, y, heading, velocityX, velocityY, angularVelocity}.ChoreoTrajectoryStateflipped()Returns this state, mirrored across the field midline.ChassisSpeedsgetChassisSpeeds()Returns the field-relative chassis speeds of this state.Pose2dgetPose()Returns the pose at this state.ChoreoTrajectoryStateinterpolate(ChoreoTrajectoryState endValue, double t)Interpolate between this state and the provided state.
-
-
-
Field Detail
-
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 X direction in m/s.
-
angularVelocity
public final double angularVelocity
The angular velocity of the state in rad/s.
-
-
Constructor Detail
-
ChoreoTrajectoryState
public ChoreoTrajectoryState(double timestamp, double x, double y, double heading, double velocityX, double velocityY, double angularVelocity)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 X direction in m/s.angularVelocity- The angular velocity of the state in rad/s.
-
-
Method Detail
-
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:
interpolatein interfaceInterpolatable<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.
-
asArray
public double[] asArray()
Returns this state as a double array: {timestamp, x, y, heading, velocityX, velocityY, angularVelocity}.- Returns:
- This state as a double array: {timestamp, x, y, heading, velocityX, velocityY, angularVelocity}.
-
flipped
public ChoreoTrajectoryState flipped()
Returns this state, mirrored across the field midline.- Returns:
- this state, mirrored across the field midline.
-
-