|
constexpr | Waypoint (std::optional< frc::Translation2d > prevControl, frc::Translation2d anchor, std::optional< frc::Translation2d > nextControl) |
|
Waypoint | flip () const |
|
|
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) |
|
|
std::optional< frc::Translation2d > | prevControl |
|
frc::Translation2d | anchor |
|
std::optional< frc::Translation2d > | nextControl |
|
◆ 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
-
prevControl | The previous control point position |
anchor | The anchor position |
nextControl | The next control point position |
◆ 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
-
anchor | The anchor point of the waypoint to create |
heading | The heading of this waypoint |
prevAnchor | The position of the previous anchor point. This can be nullopt for the start point |
nextAnchor | The position of the next anchor point. This can be nullopt for the end point |
- Returns
- Waypoint with auto calculated control points
◆ flip()
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
-
waypointJson | JSON object representing a waypoint |
- Returns
- The waypoint created from JSON
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/path/Waypoint.h
- src/main/native/cpp/pathplanner/lib/path/Waypoint.cpp