Package edu.wpi.first.math.trajectory
Class Trajectory
java.lang.Object
edu.wpi.first.math.trajectory.Trajectory
public class Trajectory extends Object
Represents a time-parameterized trajectory. The trajectory contains of various States that
represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
Trajectory.State
Represents a time-parameterized trajectory. -
Constructor Summary
Constructors Constructor Description Trajectory()
Constructs an empty trajectory.Trajectory(List<Trajectory.State> states)
Constructs a trajectory from a vector of states. -
Method Summary
Modifier and Type Method Description Trajectory
concatenate(Trajectory other)
Concatenates another trajectory to the current trajectory.boolean
equals(Object obj)
Pose2d
getInitialPose()
Returns the initial pose of the trajectory.List<Trajectory.State>
getStates()
Return the states of the trajectory.double
getTotalTimeSeconds()
Returns the overall duration of the trajectory.int
hashCode()
Trajectory
relativeTo(Pose2d pose)
Transforms all poses in the trajectory so that they are relative to the given pose.Trajectory.State
sample(double timeSeconds)
Sample the trajectory at a point in time.String
toString()
Trajectory
transformBy(Transform2d transform)
Transforms all poses in the trajectory by the given transform.
-
Constructor Details
-
Trajectory
public Trajectory()Constructs an empty trajectory. -
Trajectory
Constructs a trajectory from a vector of states.- Parameters:
states
- A vector of states.
-
-
Method Details
-
getInitialPose
Returns the initial pose of the trajectory.- Returns:
- The initial pose of the trajectory.
-
getTotalTimeSeconds
Returns the overall duration of the trajectory.- Returns:
- The duration of the trajectory.
-
getStates
Return the states of the trajectory.- Returns:
- The states of the trajectory.
-
sample
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.
-
transformBy
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.
-
relativeTo
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.
-
concatenate
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.
-
toString
-
hashCode
-
equals
-