Package com.pathplanner.lib.trajectory
Class PathPlannerTrajectory
java.lang.Object
com.pathplanner.lib.trajectory.PathPlannerTrajectory
Trajectory generated for a PathPlanner path
-
Constructor Summary
ConstructorDescriptionPathPlannerTrajectory
(PathPlannerPath path, ChassisSpeeds startingSpeeds, Rotation2d startingRotation, RobotConfig config) Generate a new trajectory for a given pathCreate a trajectory with pre-generated statesPathPlannerTrajectory
(List<PathPlannerTrajectoryState> states, List<Event> events) Create a trajectory with pre-generated states and list of events -
Method Summary
Modifier and TypeMethodDescriptionflip()
Flip this trajectory for the other side of the field, maintaining a blue alliance originGet the end state of the trajectoryGet all the events to run while following this trajectoryGet the initial robot pose at the start of the trajectoryGet the initial state of the trajectorygetState
(int index) Get the goal state at the given indexGet all the pre-generated states in the trajectoryedu.wpi.first.units.measure.Time
Get the total run time of the trajectorydouble
Get the total run time of the trajectorysample
(double time) Get the target state at the given point in time along the trajectorysample
(edu.wpi.first.units.measure.Time time) Get the target state at the given point in time along the trajectory
-
Constructor Details
-
PathPlannerTrajectory
Create a trajectory with pre-generated states and list of events- Parameters:
states
- Pre-generated statesevents
- Events for this trajectory
-
PathPlannerTrajectory
Create a trajectory with pre-generated states- Parameters:
states
- Pre-generated states
-
PathPlannerTrajectory
public PathPlannerTrajectory(PathPlannerPath path, ChassisSpeeds startingSpeeds, Rotation2d startingRotation, RobotConfig config) Generate a new trajectory for a given path- Parameters:
path
- The path to generate a trajectory forstartingSpeeds
- The starting robot-relative chassis speeds of the robotstartingRotation
- The starting field-relative rotation of the robotconfig
- TheRobotConfig
describing the robot
-
-
Method Details
-
getEvents
Get all the events to run while following this trajectory- Returns:
- Events in this trajectory
-
getStates
Get all the pre-generated states in the trajectory- Returns:
- List of all states
-
getState
Get the goal state at the given index- Parameters:
index
- Index of the state to get- Returns:
- The state at the given index
-
getInitialState
Get the initial state of the trajectory- Returns:
- The initial state
-
getEndState
Get the end state of the trajectory- Returns:
- The end state
-
getTotalTimeSeconds
public double getTotalTimeSeconds()Get the total run time of the trajectory- Returns:
- Total run time in seconds
-
getTotalTime
public edu.wpi.first.units.measure.Time getTotalTime()Get the total run time of the trajectory- Returns:
- Total run time
-
getInitialPose
Get the initial robot pose at the start of the trajectory- Returns:
- Pose of the robot at the initial state
-
sample
Get the target state at the given point in time along the trajectory- Parameters:
time
- The time to sample the trajectory at in seconds- Returns:
- The target state
-
sample
Get the target state at the given point in time along the trajectory- Parameters:
time
- The time to sample the trajectory at- Returns:
- The target state
-
flip
Flip this trajectory for the other side of the field, maintaining a blue alliance origin- Returns:
- This trajectory with all states flipped to the other side of the field
-