PathPlannerLib
Loading...
Searching...
No Matches
ConstraintsZone.h
1#pragma once
2
3#include "pathplanner/lib/path/PathConstraints.h"
4#include <wpi/json.h>
5
6namespace pathplanner {
8public:
16 constexpr ConstraintsZone(double minWaypointRelativePos,
17 double maxWaypointRelativePos, PathConstraints constraints) : m_minPos(
18 minWaypointRelativePos), m_maxPos(maxWaypointRelativePos), m_constraints(
19 constraints) {
20 }
21
28 static ConstraintsZone fromJson(const wpi::json &json);
29
35 constexpr double getMinWaypointRelativePos() const {
36 return m_minPos;
37 }
38
44 constexpr double getMaxWaypointRelativePos() const {
45 return m_maxPos;
46 }
47
53 constexpr const PathConstraints& getConstraints() const {
54 return m_constraints;
55 }
56
57 inline bool operator==(const ConstraintsZone &other) const {
58 return std::abs(m_minPos - other.m_minPos) < 1E-9
59 && std::abs(m_maxPos - other.m_maxPos) < 1E-9
60 && m_constraints == other.m_constraints;
61 }
62
63private:
64 double m_minPos;
65 double m_maxPos;
66 PathConstraints m_constraints;
67};
68}
Definition: ConstraintsZone.h:7
constexpr double getMinWaypointRelativePos() const
Definition: ConstraintsZone.h:35
constexpr ConstraintsZone(double minWaypointRelativePos, double maxWaypointRelativePos, PathConstraints constraints)
Definition: ConstraintsZone.h:16
static ConstraintsZone fromJson(const wpi::json &json)
Definition: ConstraintsZone.cpp:6
constexpr const PathConstraints & getConstraints() const
Definition: ConstraintsZone.h:53
constexpr double getMaxWaypointRelativePos() const
Definition: ConstraintsZone.h:44
Definition: PathConstraints.h:12