WPILibC++ 2024.3.2
|
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine). More...
#include <frc/geometry/Rotation2d.h>
Public Member Functions | |
constexpr | Rotation2d ()=default |
Constructs a Rotation2d with a default angle of 0 degrees. More... | |
constexpr | Rotation2d (units::angle_unit auto value) |
Constructs a Rotation2d with the given angle. More... | |
constexpr | Rotation2d (double x, double y) |
Constructs a Rotation2d with the given x and y (cosine and sine) components. More... | |
constexpr Rotation2d | operator+ (const Rotation2d &other) const |
Adds two rotations together, with the result being bounded between -pi and pi. More... | |
constexpr Rotation2d | operator- (const Rotation2d &other) const |
Subtracts the new rotation from the current rotation and returns the new rotation. More... | |
constexpr Rotation2d | operator- () const |
Takes the inverse of the current rotation. More... | |
constexpr Rotation2d | operator* (double scalar) const |
Multiplies the current rotation by a scalar. More... | |
constexpr Rotation2d | operator/ (double scalar) const |
Divides the current rotation by a scalar. More... | |
constexpr bool | operator== (const Rotation2d &other) const |
Checks equality between this Rotation2d and another object. More... | |
constexpr Rotation2d | RotateBy (const Rotation2d &other) const |
Adds the new rotation to the current rotation using a rotation matrix. More... | |
constexpr units::radian_t | Radians () const |
Returns the radian value of the rotation. More... | |
constexpr units::degree_t | Degrees () const |
Returns the degree value of the rotation. More... | |
constexpr double | Cos () const |
Returns the cosine of the rotation. More... | |
constexpr double | Sin () const |
Returns the sine of the rotation. More... | |
constexpr double | Tan () const |
Returns the tangent of the rotation. More... | |
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
The angle is continuous, that is if a Rotation2d is constructed with 361 degrees, it will return 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the rotations as it sweeps past from 360 to 0 on the second time around.
|
constexprdefault |
Constructs a Rotation2d with a default angle of 0 degrees.
|
constexpr |
Constructs a Rotation2d with the given angle.
value | The value of the angle. |
|
constexpr |
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. |
|
inlineconstexpr |
Returns the cosine of the rotation.
|
inlineconstexpr |
Returns the degree value of the rotation.
|
constexpr |
Multiplies the current rotation by a scalar.
scalar | The scalar. |
|
constexpr |
Adds two rotations together, with the result being bounded between -pi and pi.
For example, Rotation2d{30_deg} + Rotation2d{60_deg}
equals Rotation2d{units::radian_t{std::numbers::pi/2.0}}
other | The rotation to add. |
|
constexpr |
Takes the inverse of the current rotation.
This is simply the negative of the current angular value.
|
constexpr |
Subtracts the new rotation from the current rotation and returns the new rotation.
For example, Rotation2d{10_deg} - Rotation2d{100_deg}
equals Rotation2d{units::radian_t{-std::numbers::pi/2.0}}
other | The rotation to subtract. |
|
constexpr |
Divides the current rotation by a scalar.
scalar | The scalar. |
|
constexpr |
Checks equality between this Rotation2d and another object.
other | The other object. |
|
inlineconstexpr |
Returns the radian value of the rotation.
|
constexpr |
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(sin_new, cos_new)
other | The rotation to rotate by. |
|
inlineconstexpr |
Returns the sine of the rotation.
|
inlineconstexpr |
Returns the tangent of the rotation.