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

Public Member Functions

PathPlannerTrajectoryState interpolate (const PathPlannerTrajectoryState &endVal, const double t) const
 
PathPlannerTrajectoryState reverse () const
 
PathPlannerTrajectoryState flip () const
 
PathPlannerTrajectoryState copyWithTime (units::second_t time) const
 

Public Attributes

units::second_t time = 0_s
 
frc::ChassisSpeeds fieldSpeeds
 
frc::Pose2d pose
 
units::meters_per_second_t linearVelocity = 0_mps
 
DriveFeedforwards feedforwards
 
frc::Rotation2d heading
 
units::meter_t deltaPos = 0_m
 
frc::Rotation2d deltaRot
 
std::vector< SwerveModuleTrajectoryStatemoduleStates
 
PathConstraints constraints
 
double waypointRelativePos = 0.0
 

Member Function Documentation

◆ copyWithTime()

PathPlannerTrajectoryState PathPlannerTrajectoryState::copyWithTime ( units::second_t  time) const

Copy this state and change the timestamp

Parameters
timeThe new time to use
Returns
Copied state with the given time

◆ flip()

PathPlannerTrajectoryState PathPlannerTrajectoryState::flip ( ) const

Flip this trajectory state for the other side of the field, maintaining a blue alliance origin

Returns
This trajectory state flipped to the other side of the field

◆ interpolate()

PathPlannerTrajectoryState PathPlannerTrajectoryState::interpolate ( const PathPlannerTrajectoryState endVal,
const double  t 
) const

Interpolate between this state and the given state

Parameters
endValState to interpolate with
tInterpolation factor (0.0-1.0)
Returns
Interpolated state

◆ reverse()

PathPlannerTrajectoryState PathPlannerTrajectoryState::reverse ( ) const

Get the state reversed, used for following a trajectory reversed with a differential drivetrain

Returns
The reversed state

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