◆ IdealStartingState()
constexpr pathplanner::IdealStartingState::IdealStartingState |
( |
units::meters_per_second_t |
velocity, |
|
|
frc::Rotation2d |
rotation |
|
) |
| |
|
inlineconstexpr |
Create a new ideal starting state
- Parameters
-
velocity | The ideal starting velocity (M/S) |
rotation | The ideal starting rotation |
◆ fromJson()
Create an ideal starting state from json
- Parameters
-
json | json 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:
- src/main/native/include/pathplanner/lib/path/IdealStartingState.h
- src/main/native/cpp/pathplanner/lib/path/IdealStartingState.cpp