Class Trajectory
- java.lang.Object
- 
- com.lightningrobotics.common.auto.trajectory.Trajectory
 
- 
 public class Trajectory extends java.lang.ObjectRepresents a time-parameterized trajectory. The trajectory contains of various States that represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
- 
- 
Constructor SummaryConstructors Constructor Description Trajectory()Constructs an empty trajectory.Trajectory(java.util.List<TrajectoryState> states)Constructs a trajectory from a vector of states.
 - 
Method SummaryAll Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description Trajectoryconcatenate(Trajectory other)Concatenates another trajectory to the current trajectory.booleanequals(java.lang.Object obj)static Trajectoryfrom(java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints, TrajectoryConfig config)Generates a trajectory from the given waypoints and config.edu.wpi.first.math.geometry.Pose2dgetInitialPose()Returns the initial pose of the trajectory.java.util.List<TrajectoryState>getStates()Return the states of the trajectory.doublegetTotalTimeSeconds()Returns the overall duration of the trajectory.TrajectoryrelativeTo(edu.wpi.first.math.geometry.Pose2d pose)Transforms all poses in the trajectory so that they are relative to the given pose.TrajectoryStatesample(double timeSeconds)Sample the trajectory at a point in time.TrajectorytransformBy(edu.wpi.first.math.geometry.Transform2d transform)Transforms all poses in the trajectory by the given transform.
 
- 
- 
- 
Constructor Detail- 
Trajectorypublic Trajectory() Constructs an empty trajectory.
 - 
Trajectorypublic Trajectory(java.util.List<TrajectoryState> states) Constructs a trajectory from a vector of states.- Parameters:
- states- A vector of states.
 
 
- 
 - 
Method Detail- 
frompublic static Trajectory from(java.util.List<edu.wpi.first.math.geometry.Pose2d> waypoints, TrajectoryConfig config) Generates a trajectory from the given waypoints and config. This method uses quintic hermite splines -- therefore, all points must be represented by Pose2d objects. Continuous curvature is guaranteed in this method.- Parameters:
- waypoints- List of waypoints..
- config- The configuration for the trajectory.
- Returns:
- The generated trajectory.
 
 - 
getInitialPosepublic edu.wpi.first.math.geometry.Pose2d getInitialPose() Returns the initial pose of the trajectory.- Returns:
- The initial pose of the trajectory.
 
 - 
getTotalTimeSecondspublic double getTotalTimeSeconds() Returns the overall duration of the trajectory.- Returns:
- The duration of the trajectory.
 
 - 
getStatespublic java.util.List<TrajectoryState> getStates() Return the states of the trajectory.- Returns:
- The states of the trajectory.
 
 - 
samplepublic TrajectoryState sample(double timeSeconds) Sample the trajectory at a point in time.- Parameters:
- timeSeconds- The point in time since the beginning of the trajectory to sample.
- Returns:
- The state at that point in time.
 
 - 
transformBypublic Trajectory transformBy(edu.wpi.first.math.geometry.Transform2d transform) Transforms all poses in the trajectory by the given transform. This is useful for converting a robot-relative trajectory into a field-relative trajectory. This works with respect to the first pose in the trajectory.- Parameters:
- transform- The transform to transform the trajectory by.
- Returns:
- The transformed trajectory.
 
 - 
relativeTopublic Trajectory relativeTo(edu.wpi.first.math.geometry.Pose2d pose) Transforms all poses in the trajectory so that they are relative to the given pose. This is useful for converting a field-relative trajectory into a robot-relative trajectory.- Parameters:
- pose- The pose that is the origin of the coordinate frame that the current trajectory will be transformed into.
- Returns:
- The transformed trajectory.
 
 - 
concatenatepublic Trajectory concatenate(Trajectory other) Concatenates another trajectory to the current trajectory. The user is responsible for making sure that the end pose of this trajectory and the start pose of the other trajectory match (if that is the desired behavior).- Parameters:
- other- The trajectory to concatenate.
- Returns:
- The concatenated trajectory.
 
 - 
equalspublic boolean equals(java.lang.Object obj) - Overrides:
- equalsin class- java.lang.Object
 
 
- 
 
-