PathPlannerLib
Loading...
Searching...
No Matches
IdealStartingState.h
1#pragma once
2
3#include <units/velocity.h>
4#include <units/math.h>
5#include <frc/geometry/Rotation2d.h>
6#include <wpi/json.h>
7
8namespace pathplanner {
10public:
17 constexpr IdealStartingState(units::meters_per_second_t velocity,
18 frc::Rotation2d rotation) : m_velocity(velocity), m_rotation(
19 rotation) {
20 }
21
28 static IdealStartingState fromJson(const wpi::json &json);
29
35 constexpr units::meters_per_second_t getVelocity() const {
36 return m_velocity;
37 }
38
44 constexpr const frc::Rotation2d& getRotation() const {
45 return m_rotation;
46 }
47
48 inline bool operator==(const IdealStartingState &other) const {
49 return std::abs(m_velocity() - other.m_velocity()) < 1E-9
50 && m_rotation == other.m_rotation;
51 }
52
53private:
54 units::meters_per_second_t m_velocity;
55 frc::Rotation2d m_rotation;
56};
57}
Definition: IdealStartingState.h:9
constexpr IdealStartingState(units::meters_per_second_t velocity, frc::Rotation2d rotation)
Definition: IdealStartingState.h:17
constexpr units::meters_per_second_t getVelocity() const
Definition: IdealStartingState.h:35
constexpr const frc::Rotation2d & getRotation() const
Definition: IdealStartingState.h:44
static IdealStartingState fromJson(const wpi::json &json)
Definition: IdealStartingState.cpp:7