◆ ConstraintsZone()
constexpr pathplanner::ConstraintsZone::ConstraintsZone |
( |
double |
minWaypointRelativePos, |
|
|
double |
maxWaypointRelativePos, |
|
|
PathConstraints |
constraints |
|
) |
| |
|
inlineconstexpr |
Create a new constraints zone
- Parameters
-
minWaypointRelativePos | Starting position of the zone |
maxWaypointRelativePos | End position of the zone |
constraints | The constraints to apply within the zone |
◆ fromJson()
Create a constraints zone from json
- Parameters
-
json | A json reference representing a constraints zone |
- Returns
- The constraints zone defined by the given json object
◆ getConstraints()
constexpr const PathConstraints & pathplanner::ConstraintsZone::getConstraints |
( |
| ) |
const |
|
inlineconstexpr |
Get the constraints for this zone
- Returns
- The constraints for this zone
◆ getMaxWaypointRelativePos()
constexpr double pathplanner::ConstraintsZone::getMaxWaypointRelativePos |
( |
| ) |
const |
|
inlineconstexpr |
Get the end position of the zone
- Returns
- Waypoint relative end position
◆ getMinWaypointRelativePos()
constexpr double pathplanner::ConstraintsZone::getMinWaypointRelativePos |
( |
| ) |
const |
|
inlineconstexpr |
Get the starting position of the zone
- Returns
- Waypoint relative starting position
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/path/ConstraintsZone.h
- src/main/native/cpp/pathplanner/lib/path/ConstraintsZone.cpp