|
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 |
|
◆ GoalEndState()
constexpr pathplanner::GoalEndState::GoalEndState |
( |
units::meters_per_second_t |
velocity, |
|
|
frc::Rotation2d |
rotation |
|
) |
| |
|
inlineconstexpr |
Create a new goal end state
- Parameters
-
velocity | The goal end velocity (M/S) |
rotation | The goal rotation |
◆ fromJson()
GoalEndState GoalEndState::fromJson |
( |
const wpi::json & |
json | ) |
|
|
static |
Create a goal end state from json
- Parameters
-
json | json 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:
- src/main/native/include/pathplanner/lib/path/GoalEndState.h
- src/main/native/cpp/pathplanner/lib/path/GoalEndState.cpp