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

Public Member Functions

constexpr RotationTarget (double waypointRelativePosition, frc::Rotation2d target)
 
constexpr double getPosition () const
 
constexpr const frc::Rotation2d & getTarget () const
 
bool operator== (const RotationTarget &other) const
 

Static Public Member Functions

static RotationTarget fromJson (const wpi::json &json)
 

Constructor & Destructor Documentation

◆ RotationTarget()

constexpr pathplanner::RotationTarget::RotationTarget ( double  waypointRelativePosition,
frc::Rotation2d  target 
)
inlineconstexpr

Create a new rotation target

Parameters
waypointRelativePositionWaypoint relative position of this target
targetTarget rotation

Member Function Documentation

◆ fromJson()

RotationTarget RotationTarget::fromJson ( const wpi::json &  json)
static

Create a rotation target from json

Parameters
jsonjson reference representing a rotation target
Returns
Rotation target defined by the given json

◆ getPosition()

constexpr double pathplanner::RotationTarget::getPosition ( ) const
inlineconstexpr

Get the waypoint relative position of this target

Returns
Waypoint relative position

◆ getTarget()

constexpr const frc::Rotation2d & pathplanner::RotationTarget::getTarget ( ) const
inlineconstexpr

Get the target rotation

Returns
Target rotation

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