public class Trajectory
extends java.lang.Object
Modifier and Type | Class and Description |
---|---|
static class |
Trajectory.State
Represents a time-parameterized trajectory.
|
Constructor and Description |
---|
Trajectory(java.util.List<Trajectory.State> states)
Constructs a trajectory from a vector of states.
|
Modifier and Type | Method and Description |
---|---|
Pose2d |
getInitialPose()
Returns the initial pose of the trajectory.
|
java.util.List<Trajectory.State> |
getStates()
Return the states of the trajectory.
|
double |
getTotalTimeSeconds()
Returns the overall duration of the trajectory.
|
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.
|
java.lang.String |
toString() |
Trajectory |
transformBy(Transform2d transform)
Transforms all poses in the trajectory by the given transform.
|
public Trajectory(java.util.List<Trajectory.State> states)
states
- A vector of states.public Pose2d getInitialPose()
public double getTotalTimeSeconds()
public java.util.List<Trajectory.State> getStates()
public Trajectory.State sample(double timeSeconds)
timeSeconds
- The point in time since the beginning of the trajectory to sample.public Trajectory transformBy(Transform2d transform)
transform
- The transform to transform the trajectory by.public Trajectory relativeTo(Pose2d pose)
pose
- The pose that is the origin of the coordinate frame that
the current trajectory will be transformed into.public java.lang.String toString()
toString
in class java.lang.Object