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

Public Member Functions

constexpr PathPoint (frc::Translation2d pos, std::optional< RotationTarget > rot, std::optional< PathConstraints > pathCostriaints)
 
constexpr PathPoint (frc::Translation2d pos)
 
PathPoint flip () const
 

Public Attributes

frc::Translation2d position
 
units::meter_t distanceAlongPath = 0_m
 
units::meters_per_second_t maxV
 
std::optional< RotationTargetrotationTarget = std::nullopt
 
std::optional< PathConstraintsconstraints = std::nullopt
 
double waypointRelativePos = 0.0
 

Member Data Documentation

◆ maxV

units::meters_per_second_t pathplanner::PathPoint::maxV
Initial value:
= units::meters_per_second_t {
std::numeric_limits<double>::infinity() }

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