RIT VEXU Core API
|
#include <rotation2d.h>
Public Member Functions | |
constexpr | Rotation2d () |
Rotation2d (const double &radians) | |
Rotation2d (const double &x, const double &y) | |
Rotation2d (const Translation2d &translation) | |
double | radians () const |
double | degrees () const |
double | revolutions () const |
double | f_cos () const |
double | f_sin () const |
double | f_tan () const |
Eigen::Matrix2d | rotation_matrix () const |
double | wrapped_radians_180 () const |
double | wrapped_degrees_180 () const |
double | wrapped_revolutions_180 () const |
double | wrapped_radians_360 () const |
double | wrapped_degrees_360 () const |
double | wrapped_revolutions_360 () const |
Rotation2d | operator+ (const Rotation2d &other) const |
Rotation2d | operator- (const Rotation2d &other) const |
Rotation2d | operator- () const |
Rotation2d | operator* (const double &scalar) const |
Rotation2d | operator/ (const double &scalar) const |
bool | operator== (const Rotation2d &other) const |
Friends | |
std::ostream & | operator<< (std::ostream &os, const Rotation2d &rotation) |
Class representing a rotation in 2d space. Stores theta in radians, as well as cos and sin.
Internally this angle is stored continuously, however there are functions that return wrapped angles: "180" is from [-pi, pi), [-180, 180), [-0.5, 0.5) "360" is from [0, 2pi), [0, 360), [0, 1)
|
inlineconstexpr |
Default Constructor for Rotation2d
Rotation2d::Rotation2d | ( | const double & | radians | ) |
Constructs a rotation with the given value in radians.
radians | the value of the rotation in radians. |
Rotation2d::Rotation2d | ( | const double & | x, |
const double & | y ) |
Constructs a rotation given x and y values. Does not have to be normalized. The angle from the x axis to the point.
[theta] = [atan2(y, x)]
x | the x value of the point |
y | the y value of the point |
Rotation2d::Rotation2d | ( | const Translation2d & | translation | ) |
Constructs a rotation given x and y values in the form of a Translation2d. Does not have to be normalized. The angle from the x axis to the point.
[theta] = [atan2(y, x)]
translation |
double Rotation2d::degrees | ( | ) | const |
Returns the degree angle value.
double Rotation2d::f_cos | ( | ) | const |
Returns the cosine of the angle value.
double Rotation2d::f_sin | ( | ) | const |
Returns the sine of the angle value.
double Rotation2d::f_tan | ( | ) | const |
Returns the tangent of the angle value.
Rotation2d Rotation2d::operator* | ( | const double & | scalar | ) | const |
Multiplies this rotation by a scalar.
scalar | the scalar value to multiply the rotation by. |
Rotation2d Rotation2d::operator+ | ( | const Rotation2d & | other | ) | const |
Adds the values of two rotations using a rotation matrix
[new_cos] = [other.cos, -other.sin][cos] [new_sin] = [other.sin, other.cos][sin] new_value = atan2(new_sin, new_cos)
other | the other rotation to add to this rotation. |
Adds the values of two rotations using a rotation matrix.
[new_cos] = [other.cos, -other.sin][cos] [new_sin] = [other.sin, other.cos][sin] new_value = atan2(new_sin, new_cos)
other | the other rotation to add to this rotation. |
Rotation2d Rotation2d::operator- | ( | ) | const |
Takes the inverse of this rotation by flipping it. Equivalent to adding 180 degrees.
Takes the inverse of this rotation by flipping it.
Rotation2d Rotation2d::operator- | ( | const Rotation2d & | other | ) | const |
Subtracts the values of two rotations.
other | the other rotation to subtract from this rotation. |
Rotation2d Rotation2d::operator/ | ( | const double & | scalar | ) | const |
Divides this rotation by a scalar.
scalar | the scalar value to divide the rotation by. |
bool Rotation2d::operator== | ( | const Rotation2d & | other | ) | const |
Compares two rotations. Returns true if their values are within 1e-9 radians of each other, to account for floating point error.
other | the other rotation to compare to |
double Rotation2d::radians | ( | ) | const |
Returns the radian angle value.
double Rotation2d::revolutions | ( | ) | const |
Returns the revolution angle value.
Eigen::Matrix2d Rotation2d::rotation_matrix | ( | ) | const |
Returns the rotation matrix equivalent to this rotation [cos, -sin] R = [sin, cos]
double Rotation2d::wrapped_degrees_180 | ( | ) | const |
Returns the degree angle value, wrapped from [-180, 180).
double Rotation2d::wrapped_degrees_360 | ( | ) | const |
Returns the degree angle value, wrapped from [0, 360).
double Rotation2d::wrapped_radians_180 | ( | ) | const |
Returns the radian angle value, wrapped from [-pi, pi).
double Rotation2d::wrapped_radians_360 | ( | ) | const |
Returns the radian angle value, wrapped from [0, 2pi).
double Rotation2d::wrapped_revolutions_180 | ( | ) | const |
Returns the revolution angle value, wrapped from [-0.5, 0.5).
double Rotation2d::wrapped_revolutions_360 | ( | ) | const |
Returns the revolution angle value, wrapped from [0, 1).
|
friend |
Sends a rotation to an output stream. Ex. std::cout << rotation;
prints "Rotation2d[rad: (radians), deg: (degrees)]"