RIT VEXU Core API
Loading...
Searching...
No Matches
rotation2d.h
1#pragma once
2
3#include "math/eigen_interface.h"
4
5#include "math/geometry/translation2d.h"
6#include <cmath>
7#include <iostream>
8#include <vector>
9
10#ifndef PI
11#define PI 3.141592654
12#endif
13
14class Translation2d;
15
26 public:
30 constexpr Rotation2d() : m_radians(0), m_cos(1), m_sin(0) {};
36 Rotation2d(const double &radians);
37
48 Rotation2d(const double &x, const double &y);
49
59 Rotation2d(const Translation2d &translation);
60
66 double radians() const;
67
73 double degrees() const;
74
80 double revolutions() const;
81
87 double f_cos() const;
88
94 double f_sin() const;
95
101 double f_tan() const;
102
110 Eigen::Matrix2d rotation_matrix() const;
111
117 double wrapped_radians_180() const;
118
124 double wrapped_degrees_180() const;
125
131 double wrapped_revolutions_180() const;
132
138 double wrapped_radians_360() const;
139
145 double wrapped_degrees_360() const;
146
152 double wrapped_revolutions_360() const;
153
165 Rotation2d operator+(const Rotation2d &other) const;
166
174 Rotation2d operator-(const Rotation2d &other) const;
175
182 Rotation2d operator-() const;
183
191 Rotation2d operator*(const double &scalar) const;
192
200 Rotation2d operator/(const double &scalar) const;
201
210 bool operator==(const Rotation2d &other) const;
211
219 friend std::ostream &operator<<(std::ostream &os, const Rotation2d &rotation);
220
221 private:
222 double m_radians;
223 double m_cos;
224 double m_sin;
225};
226
227// functions that don't belong in the class because they're useful elsewhere
228
234Rotation2d from_radians(const double &radians);
235
241Rotation2d from_degrees(const double &degrees);
242
248Rotation2d from_revolutions(const double &revolutions);
249
257double wrap_radians_180(const double &angle);
258
266double wrap_degrees_180(const double &angle);
267
275double wrap_revolutions_180(const double &angle);
276
284double wrap_radians_360(const double &angle);
285
293double wrap_degrees_360(const double &angle);
294
302double wrap_revolutions_360(const double &angle);
303
309double deg2rad(double deg);
310
317double rad2deg(double r);
318
327Rotation2d unwrapped_mean(const std::vector<Rotation2d> &list);
328
337Rotation2d wrapped_mean(const std::vector<Rotation2d> &list);
Definition rotation2d.h:25
Eigen::Matrix2d rotation_matrix() const
Definition rotation2d.cpp:110
bool operator==(const Rotation2d &other) const
Definition rotation2d.cpp:221
double wrapped_revolutions_180() const
Definition rotation2d.cpp:131
double wrapped_revolutions_360() const
Definition rotation2d.cpp:152
double wrapped_radians_360() const
Definition rotation2d.cpp:138
friend std::ostream & operator<<(std::ostream &os, const Rotation2d &rotation)
Definition rotation2d.cpp:232
double f_tan() const
Definition rotation2d.cpp:101
double f_cos() const
Definition rotation2d.cpp:87
double wrapped_radians_180() const
Definition rotation2d.cpp:117
constexpr Rotation2d()
Definition rotation2d.h:30
double wrapped_degrees_360() const
Definition rotation2d.cpp:145
double f_sin() const
Definition rotation2d.cpp:94
double radians() const
Definition rotation2d.cpp:66
double degrees() const
Definition rotation2d.cpp:73
Rotation2d operator+(const Rotation2d &other) const
Definition rotation2d.cpp:175
Rotation2d operator/(const double &scalar) const
Definition rotation2d.cpp:211
Rotation2d operator-() const
Definition rotation2d.cpp:193
Rotation2d operator*(const double &scalar) const
Definition rotation2d.cpp:202
double wrapped_degrees_180() const
Definition rotation2d.cpp:124
double revolutions() const
Definition rotation2d.cpp:80
Definition translation2d.h:22