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

Public Member Functions

constexpr GoalEndState (units::meters_per_second_t velocity, frc::Rotation2d rotation)
 
constexpr units::meters_per_second_t getVelocity () const
 
constexpr const frc::Rotation2d & getRotation () const
 
bool operator== (const GoalEndState &other) const
 

Static Public Member Functions

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

Constructor & Destructor Documentation

◆ GoalEndState()

constexpr pathplanner::GoalEndState::GoalEndState ( units::meters_per_second_t  velocity,
frc::Rotation2d  rotation 
)
inlineconstexpr

Create a new goal end state

Parameters
velocityThe goal end velocity (M/S)
rotationThe goal rotation

Member Function Documentation

◆ fromJson()

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

Create a goal end state from json

Parameters
jsonjson reference representing a goal end state
Returns
The goal end state defined by the given json

◆ getRotation()

constexpr const frc::Rotation2d & pathplanner::GoalEndState::getRotation ( ) const
inlineconstexpr

Get the goal end rotation

Returns
Goal rotation

◆ getVelocity()

constexpr units::meters_per_second_t pathplanner::GoalEndState::getVelocity ( ) const
inlineconstexpr

Get the goal end velocity

Returns
Goal end velocity (M/S)

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