public class Trajectory
Time-parametrized trajectory of poses.
Constructor and Description |
---|
Trajectory(java.util.List<? extends com.acmerobotics.roadrunner.trajectory.TrajectorySegment> segments)
Time-parametrized trajectory of poses.
|
Trajectory()
Time-parametrized trajectory of poses.
|
Modifier and Type | Method and Description |
---|---|
Pose2d |
acceleration(double time)
Returns the pose acceleration at the specified time.
|
double |
duration()
Returns the trajectory duration.
|
Pose2d |
end()
Returns the end pose.
|
Pose2d |
endAcceleration()
Returns the end pose acceleration.
|
Pose2d |
endVelocity()
Returns the end pose velocity.
|
Pose2d |
get(double time)
Returns the pose at the specified time.
|
java.util.List<com.acmerobotics.roadrunner.trajectory.TrajectorySegment> |
getSegments()
trajectory segments
|
Pose2d |
start()
Returns the start pose.
|
Pose2d |
startAcceleration()
Returns the start pose acceleration.
|
Pose2d |
startVelocity()
Returns the start pose velocity.
|
Pose2d |
velocity(double time)
Returns the pose velocity at the specified time.
|
public Trajectory(java.util.List<? extends com.acmerobotics.roadrunner.trajectory.TrajectorySegment> segments)
Time-parametrized trajectory of poses.
segments
- trajectory segmentssegments
- trajectory segmentspublic Trajectory()
Time-parametrized trajectory of poses.
public double duration()
Returns the trajectory duration.
public Pose2d get(double time)
Returns the pose at the specified time.
public Pose2d velocity(double time)
Returns the pose velocity at the specified time.
public Pose2d acceleration(double time)
Returns the pose acceleration at the specified time.
public Pose2d start()
Returns the start pose.
public Pose2d startVelocity()
Returns the start pose velocity.
public Pose2d startAcceleration()
Returns the start pose acceleration.
public Pose2d end()
Returns the end pose.
public Pose2d endVelocity()
Returns the end pose velocity.
public Pose2d endAcceleration()
Returns the end pose acceleration.
public java.util.List<com.acmerobotics.roadrunner.trajectory.TrajectorySegment> getSegments()
trajectory segments