PathPlannerLib
Loading...
Searching...
No Matches
RotationTarget.h
1#pragma once
2
3#include <frc/geometry/Rotation2d.h>
4#include <wpi/json.h>
5
6namespace pathplanner {
8public:
15 constexpr RotationTarget(double waypointRelativePosition,
16 frc::Rotation2d target) : m_position(waypointRelativePosition), m_target(
17 target) {
18 }
19
26 static RotationTarget fromJson(const wpi::json &json);
27
33 constexpr double getPosition() const {
34 return m_position;
35 }
36
42 constexpr const frc::Rotation2d& getTarget() const {
43 return m_target;
44 }
45
46 inline bool operator==(const RotationTarget &other) const {
47 return std::abs(m_position - other.m_position) < 1E-9
48 && m_target == other.m_target;
49 }
50
51private:
52 double m_position;
53 frc::Rotation2d m_target;
54};
55}
Definition: RotationTarget.h:7
static RotationTarget fromJson(const wpi::json &json)
Definition: RotationTarget.cpp:6
constexpr RotationTarget(double waypointRelativePosition, frc::Rotation2d target)
Definition: RotationTarget.h:15
constexpr const frc::Rotation2d & getTarget() const
Definition: RotationTarget.h:42
constexpr double getPosition() const
Definition: RotationTarget.h:33