◆ PathPlannerTrajectory() [1/3]
pathplanner::PathPlannerTrajectory::PathPlannerTrajectory |
( |
std::vector< PathPlannerTrajectoryState > |
states, |
|
|
std::vector< std::shared_ptr< Event > > |
events |
|
) |
| |
|
inline |
Create a trajectory with pre-generated states and list of events
- Parameters
-
states | Pre-generated states |
events | Events for this trajectory |
◆ PathPlannerTrajectory() [2/3]
Create a trajectory with pre-generated states
- Parameters
-
states | Pre-generated states |
◆ PathPlannerTrajectory() [3/3]
PathPlannerTrajectory::PathPlannerTrajectory |
( |
std::shared_ptr< PathPlannerPath > |
path, |
|
|
const frc::ChassisSpeeds & |
startingSpeeds, |
|
|
const frc::Rotation2d & |
startingRotation, |
|
|
const RobotConfig & |
config |
|
) |
| |
Generate a new trajectory for a given path
- Parameters
-
path | The path to generate a trajectory for |
startingSpeeds | The starting robot-relative chassis speeds of the robot |
startingRotation | The starting field-relative rotation of the robot |
config | The RobotConfig describing the robot |
◆ 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
◆ getEndState()
Get the end state of the trajectory
- Returns
- The end state
◆ getEvents()
std::vector< std::shared_ptr< Event > > pathplanner::PathPlannerTrajectory::getEvents |
( |
| ) |
|
|
inline |
Get all the events to run while following this trajectory
- Returns
- Events in this trajectory
◆ getInitialPose()
frc::Pose2d pathplanner::PathPlannerTrajectory::getInitialPose |
( |
| ) |
|
|
inline |
Get the initial robot pose at the start of the trajectory
- Returns
- Pose of the robot at the initial state
◆ getInitialState()
Get the initial state of the trajectory
- Returns
- The initial state
◆ getState()
Get the goal state at the given index
- Parameters
-
index | Index of the state to get |
- Returns
- The state at the given index
◆ getStates()
Get all of the pre-generated states in the trajectory
- Returns
- vector of all states
◆ getTotalTime()
units::second_t pathplanner::PathPlannerTrajectory::getTotalTime |
( |
| ) |
|
|
inline |
Get the total run time of the trajectory
- Returns
- Total run time in seconds
◆ 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
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/trajectory/PathPlannerTrajectory.h
- src/main/native/cpp/pathplanner/lib/trajectory/PathPlannerTrajectory.cpp