WPILibC++
2021.2.2
|
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine). More...
#include <Rotation2d.h>
Public Member Functions | |
constexpr | Rotation2d ()=default |
Constructs a Rotation2d with a default angle of 0 degrees. | |
Rotation2d (units::radian_t value) | |
Constructs a Rotation2d with the given radian value. More... | |
Rotation2d (units::degree_t value) | |
Constructs a Rotation2d with the given degree value. More... | |
Rotation2d (double x, double y) | |
Constructs a Rotation2d with the given x and y (cosine and sine) components. More... | |
Rotation2d | operator+ (const Rotation2d &other) const |
Adds two rotations together, with the result being bounded between -pi and pi. More... | |
Rotation2d & | operator+= (const Rotation2d &other) |
Adds a rotation to the current rotation. More... | |
Rotation2d | operator- (const Rotation2d &other) const |
Subtracts the new rotation from the current rotation and returns the new rotation. More... | |
Rotation2d & | operator-= (const Rotation2d &other) |
Subtracts the new rotation from the current rotation. More... | |
Rotation2d | operator- () const |
Takes the inverse of the current rotation. More... | |
Rotation2d | operator* (double scalar) const |
Multiplies the current rotation by a scalar. More... | |
bool | operator== (const Rotation2d &other) const |
Checks equality between this Rotation2d and another object. More... | |
bool | operator!= (const Rotation2d &other) const |
Checks inequality between this Rotation2d and another object. More... | |
Rotation2d | RotateBy (const Rotation2d &other) const |
Adds the new rotation to the current rotation using a rotation matrix. More... | |
units::radian_t | Radians () const |
Returns the radian value of the rotation. More... | |
units::degree_t | Degrees () const |
Returns the degree value of the rotation. More... | |
double | Cos () const |
Returns the cosine of the rotation. More... | |
double | Sin () const |
Returns the sine of the rotation. More... | |
double | Tan () const |
Returns the tangent of the rotation. More... | |
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
frc::Rotation2d::Rotation2d | ( | units::radian_t | value | ) |
Constructs a Rotation2d with the given radian value.
value | The value of the angle in radians. |
frc::Rotation2d::Rotation2d | ( | units::degree_t | value | ) |
Constructs a Rotation2d with the given degree value.
value | The value of the angle in degrees. |
frc::Rotation2d::Rotation2d | ( | double | x, |
double | y | ||
) |
Constructs a Rotation2d with the given x and y (cosine and sine) components.
The x and y don't have to be normalized.
x | The x component or cosine of the rotation. |
y | The y component or sine of the rotation. |
|
inline |
Returns the cosine of the rotation.
|
inline |
Returns the degree value of the rotation.
bool frc::Rotation2d::operator!= | ( | const Rotation2d & | other | ) | const |
Checks inequality between this Rotation2d and another object.
other | The other object. |
Rotation2d frc::Rotation2d::operator* | ( | double | scalar | ) | const |
Multiplies the current rotation by a scalar.
scalar | The scalar. |
Rotation2d frc::Rotation2d::operator+ | ( | const Rotation2d & | other | ) | const |
Adds two rotations together, with the result being bounded between -pi and pi.
For example, Rotation2d.FromDegrees(30) + Rotation2d.FromDegrees(60) = Rotation2d{-pi/2}
other | The rotation to add. |
Rotation2d& frc::Rotation2d::operator+= | ( | const Rotation2d & | other | ) |
Adds a rotation to the current rotation.
This is similar to the + operator except that it mutates the current object.
other | The rotation to add. |
Rotation2d frc::Rotation2d::operator- | ( | ) | const |
Takes the inverse of the current rotation.
This is simply the negative of the current angular value.
Rotation2d frc::Rotation2d::operator- | ( | const Rotation2d & | other | ) | const |
Subtracts the new rotation from the current rotation and returns the new rotation.
For example, Rotation2d.FromDegrees(10) - Rotation2d.FromDegrees(100) = Rotation2d{-pi/2}
other | The rotation to subtract. |
Rotation2d& frc::Rotation2d::operator-= | ( | const Rotation2d & | other | ) |
Subtracts the new rotation from the current rotation.
This is similar to the - operator except that it mutates the current object.
other | The rotation to subtract. |
bool frc::Rotation2d::operator== | ( | const Rotation2d & | other | ) | const |
Checks equality between this Rotation2d and another object.
other | The other object. |
|
inline |
Returns the radian value of the rotation.
Rotation2d frc::Rotation2d::RotateBy | ( | const Rotation2d & | other | ) | const |
Adds the new rotation to the current rotation using a rotation matrix.
[cos_new] [other.cos, -other.sin][cos] [sin_new] = [other.sin, other.cos][sin]
value_new = std::atan2(cos_new, sin_new)
other | The rotation to rotate by. |
|
inline |
Returns the sine of the rotation.
|
inline |
Returns the tangent of the rotation.