PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::PathPlannerTrajectory Class Reference

Public Member Functions

 PathPlannerTrajectory (std::vector< PathPlannerTrajectoryState > states, std::vector< std::shared_ptr< Event > > events)
 
 PathPlannerTrajectory (std::vector< PathPlannerTrajectoryState > states)
 
 PathPlannerTrajectory (std::shared_ptr< PathPlannerPath > path, const frc::ChassisSpeeds &startingSpeeds, const frc::Rotation2d &startingRotation, const RobotConfig &config)
 
std::vector< std::shared_ptr< Event > > getEvents ()
 
constexpr std::vector< PathPlannerTrajectoryState > & getStates ()
 
PathPlannerTrajectoryState getState (size_t index)
 
PathPlannerTrajectoryState getInitialState ()
 
PathPlannerTrajectoryState getEndState ()
 
units::second_t getTotalTime ()
 
frc::Pose2d getInitialPose ()
 
PathPlannerTrajectoryState sample (const units::second_t time)
 
PathPlannerTrajectory flip ()
 

Constructor & Destructor Documentation

◆ 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
statesPre-generated states
eventsEvents for this trajectory

◆ PathPlannerTrajectory() [2/3]

pathplanner::PathPlannerTrajectory::PathPlannerTrajectory ( std::vector< PathPlannerTrajectoryState states)
inline

Create a trajectory with pre-generated states

Parameters
statesPre-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
pathThe path to generate a trajectory for
startingSpeedsThe starting robot-relative chassis speeds of the robot
startingRotationThe starting field-relative rotation of the robot
configThe RobotConfig describing the robot

Member Function Documentation

◆ flip()

PathPlannerTrajectory pathplanner::PathPlannerTrajectory::flip ( )
inline

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()

PathPlannerTrajectoryState pathplanner::PathPlannerTrajectory::getEndState ( )
inline

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()

PathPlannerTrajectoryState pathplanner::PathPlannerTrajectory::getInitialState ( )
inline

Get the initial state of the trajectory

Returns
The initial state

◆ getState()

PathPlannerTrajectoryState pathplanner::PathPlannerTrajectory::getState ( size_t  index)
inline

Get the goal state at the given index

Parameters
indexIndex of the state to get
Returns
The state at the given index

◆ getStates()

constexpr std::vector< PathPlannerTrajectoryState > & pathplanner::PathPlannerTrajectory::getStates ( )
inlineconstexpr

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()

PathPlannerTrajectoryState PathPlannerTrajectory::sample ( const units::second_t  time)

Get the target state at the given point in time along the trajectory

Parameters
timeThe time to sample the trajectory at in seconds
Returns
The target state

The documentation for this class was generated from the following files: