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

Public Member Functions

constexpr ConstraintsZone (double minWaypointRelativePos, double maxWaypointRelativePos, PathConstraints constraints)
 
constexpr double getMinWaypointRelativePos () const
 
constexpr double getMaxWaypointRelativePos () const
 
constexpr const PathConstraintsgetConstraints () const
 
bool operator== (const ConstraintsZone &other) const
 

Static Public Member Functions

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

Constructor & Destructor Documentation

◆ ConstraintsZone()

constexpr pathplanner::ConstraintsZone::ConstraintsZone ( double  minWaypointRelativePos,
double  maxWaypointRelativePos,
PathConstraints  constraints 
)
inlineconstexpr

Create a new constraints zone

Parameters
minWaypointRelativePosStarting position of the zone
maxWaypointRelativePosEnd position of the zone
constraintsThe constraints to apply within the zone

Member Function Documentation

◆ fromJson()

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

Create a constraints zone from json

Parameters
jsonA 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: