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

Public Member Functions

constexpr Waypoint (std::optional< frc::Translation2d > prevControl, frc::Translation2d anchor, std::optional< frc::Translation2d > nextControl)
 
Waypoint flip () const
 

Static Public Member Functions

static Waypoint autoControlPoints (frc::Translation2d anchor, frc::Rotation2d heading, std::optional< frc::Translation2d > prevAnchor, std::optional< frc::Translation2d > nextAnchor)
 
static Waypoint fromJson (const wpi::json &waypointJson)
 

Public Attributes

std::optional< frc::Translation2d > prevControl
 
frc::Translation2d anchor
 
std::optional< frc::Translation2d > nextControl
 

Constructor & Destructor Documentation

◆ Waypoint()

constexpr pathplanner::Waypoint::Waypoint ( std::optional< frc::Translation2d >  prevControl,
frc::Translation2d  anchor,
std::optional< frc::Translation2d >  nextControl 
)
inlineconstexpr

Create a waypoint from its anchor point and control points

Parameters
prevControlThe previous control point position
anchorThe anchor position
nextControlThe next control point position

Member Function Documentation

◆ autoControlPoints()

Waypoint Waypoint::autoControlPoints ( frc::Translation2d  anchor,
frc::Rotation2d  heading,
std::optional< frc::Translation2d >  prevAnchor,
std::optional< frc::Translation2d >  nextAnchor 
)
static

Create a waypoint with auto calculated control points based on the positions of adjacent waypoints. This is used internally, and you probably shouldn't use this.

Parameters
anchorThe anchor point of the waypoint to create
headingThe heading of this waypoint
prevAnchorThe position of the previous anchor point. This can be nullopt for the start point
nextAnchorThe position of the next anchor point. This can be nullopt for the end point
Returns
Waypoint with auto calculated control points

◆ flip()

Waypoint Waypoint::flip ( ) const

Flip this waypoint to the other side of the field, maintaining a blue alliance origin

Returns
The flipped waypoint

◆ fromJson()

Waypoint Waypoint::fromJson ( const wpi::json &  waypointJson)
static

Create a waypoint from JSON

Parameters
waypointJsonJSON object representing a waypoint
Returns
The waypoint created from JSON

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