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

Public Member Functions

constexpr IdealStartingState (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 IdealStartingState &other) const
 

Static Public Member Functions

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

Constructor & Destructor Documentation

◆ IdealStartingState()

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

Create a new ideal starting state

Parameters
velocityThe ideal starting velocity (M/S)
rotationThe ideal starting rotation

Member Function Documentation

◆ fromJson()

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

Create an ideal starting state from json

Parameters
jsonjson reference representing an ideal starting state
Returns
The ideal starting state defined by the given json

◆ getRotation()

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

Get the ideal starting rotation

Returns
Ideal starting rotation

◆ getVelocity()

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

Get the ideal starting velocity

Returns
Ideal starting velocity (M/S)

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