Package edu.wpi.first.math.trajectory
Class Trajectory.State
- java.lang.Object
-
- edu.wpi.first.math.trajectory.Trajectory.State
-
- Enclosing class:
- Trajectory
public static class Trajectory.State 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.
-
-
Field Summary
Fields Modifier and Type Field Description double
accelerationMetersPerSecondSq
double
curvatureRadPerMeter
Pose2d
poseMeters
double
timeSeconds
double
velocityMetersPerSecond
-
-
-
Field Detail
-
timeSeconds
public double timeSeconds
-
velocityMetersPerSecond
public double velocityMetersPerSecond
-
accelerationMetersPerSecondSq
public double accelerationMetersPerSecondSq
-
poseMeters
public Pose2d poseMeters
-
curvatureRadPerMeter
public double curvatureRadPerMeter
-
-
Constructor Detail
-
State
public State()
-
State
public State(double timeSeconds, double velocityMetersPerSecond, double accelerationMetersPerSecondSq, Pose2d poseMeters, double curvatureRadPerMeter)
Constructs a State with the specified parameters.- Parameters:
timeSeconds
- The time elapsed since the beginning of the trajectory.velocityMetersPerSecond
- The speed at that point of the trajectory.accelerationMetersPerSecondSq
- The acceleration at that point of the trajectory.poseMeters
- The pose at that point of the trajectory.curvatureRadPerMeter
- The curvature at that point of the trajectory.
-
-