RIT VEXU Core API
Loading...
Searching...
No Matches
rotation2d.h
1#pragma once
2#undef __ARM_NEON__
3#undef __ARM_NEON
4#include <Eigen/Dense>
5
6#include "core/utils/math/geometry/translation2d.h"
7#include <cmath>
8#include <iostream>
9#include <vector>
10
11#ifndef PI
12#define PI 3.141592654
13#endif
14
15class Translation2d;
16
27 public:
31 constexpr Rotation2d() : m_radians(0), m_cos(1), m_sin(0) {};
37 Rotation2d(const double &radians);
38
49 Rotation2d(const double &x, const double &y);
50
60 Rotation2d(const Translation2d &translation);
61
67 double radians() const;
68
74 double degrees() const;
75
81 double revolutions() const;
82
88 double f_cos() const;
89
95 double f_sin() const;
96
102 double f_tan() const;
103
111 Eigen::Matrix2d rotation_matrix() const;
112
118 double wrapped_radians_180() const;
119
125 double wrapped_degrees_180() const;
126
132 double wrapped_revolutions_180() const;
133
139 double wrapped_radians_360() const;
140
146 double wrapped_degrees_360() const;
147
153 double wrapped_revolutions_360() const;
154
166 Rotation2d operator+(const Rotation2d &other) const;
167
175 Rotation2d operator-(const Rotation2d &other) const;
176
183 Rotation2d operator-() const;
184
192 Rotation2d operator*(const double &scalar) const;
193
201 Rotation2d operator/(const double &scalar) const;
202
211 bool operator==(const Rotation2d &other) const;
212
220 friend std::ostream &operator<<(std::ostream &os, const Rotation2d &rotation);
221
222 private:
223 double m_radians;
224 double m_cos;
225 double m_sin;
226};
227
228// functions that don't belong in the class because they're useful elsewhere
229
235Rotation2d from_radians(const double &radians);
236
242Rotation2d from_degrees(const double &degrees);
243
249Rotation2d from_revolutions(const double &revolutions);
250
258double wrap_radians_180(const double &angle);
259
267double wrap_degrees_180(const double &angle);
268
276double wrap_revolutions_180(const double &angle);
277
285double wrap_radians_360(const double &angle);
286
294double wrap_degrees_360(const double &angle);
295
303double wrap_revolutions_360(const double &angle);
304
310double deg2rad(double deg);
311
318double rad2deg(double r);
319
328Rotation2d unwrapped_mean(const std::vector<Rotation2d> &list);
329
338Rotation2d wrapped_mean(const std::vector<Rotation2d> &list);
Definition rotation2d.h:26
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:31
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:21