WPILibC++ 2023.4.3-108-ge5452e3
frc::Rotation2d Class Reference

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::radian_t value)
 Constructs a Rotation2d with the given radian value. More...
 
constexpr Rotation2d (units::degree_t value)
 Constructs a Rotation2d with the given degree value. 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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ Rotation2d() [1/4]

constexpr frc::Rotation2d::Rotation2d ( )
constexprdefault

Constructs a Rotation2d with a default angle of 0 degrees.

◆ Rotation2d() [2/4]

constexpr frc::Rotation2d::Rotation2d ( units::radian_t  value)
constexpr

Constructs a Rotation2d with the given radian value.

Parameters
valueThe value of the angle in radians.

◆ Rotation2d() [3/4]

constexpr frc::Rotation2d::Rotation2d ( units::degree_t  value)
constexpr

Constructs a Rotation2d with the given degree value.

Parameters
valueThe value of the angle in degrees.

◆ Rotation2d() [4/4]

constexpr frc::Rotation2d::Rotation2d ( double  x,
double  y 
)
constexpr

Constructs a Rotation2d with the given x and y (cosine and sine) components.

The x and y don't have to be normalized.

Parameters
xThe x component or cosine of the rotation.
yThe y component or sine of the rotation.

Member Function Documentation

◆ Cos()

constexpr double frc::Rotation2d::Cos ( ) const
inlineconstexpr

Returns the cosine of the rotation.

Returns
The cosine of the rotation.

◆ Degrees()

constexpr units::degree_t frc::Rotation2d::Degrees ( ) const
inlineconstexpr

Returns the degree value of the rotation.

Returns
The degree value of the rotation.
See also
InputModulus to constrain the angle within (-180, 180]

◆ operator*()

constexpr Rotation2d frc::Rotation2d::operator* ( double  scalar) const
constexpr

Multiplies the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation2d.

◆ operator+()

constexpr Rotation2d frc::Rotation2d::operator+ ( const Rotation2d other) const
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}}

Parameters
otherThe rotation to add.
Returns
The sum of the two rotations.

◆ operator-() [1/2]

constexpr Rotation2d frc::Rotation2d::operator- ( ) const
constexpr

Takes the inverse of the current rotation.

This is simply the negative of the current angular value.

Returns
The inverse of the current rotation.

◆ operator-() [2/2]

constexpr Rotation2d frc::Rotation2d::operator- ( const Rotation2d other) const
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}}

Parameters
otherThe rotation to subtract.
Returns
The difference between the two rotations.

◆ operator/()

constexpr Rotation2d frc::Rotation2d::operator/ ( double  scalar) const
constexpr

Divides the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation2d.

◆ operator==()

constexpr bool frc::Rotation2d::operator== ( const Rotation2d other) const
constexpr

Checks equality between this Rotation2d and another object.

Parameters
otherThe other object.
Returns
Whether the two objects are equal.

◆ Radians()

constexpr units::radian_t frc::Rotation2d::Radians ( ) const
inlineconstexpr

Returns the radian value of the rotation.

Returns
The radian value of the rotation.
See also
AngleModulus to constrain the angle within (-pi, pi]

◆ RotateBy()

constexpr Rotation2d frc::Rotation2d::RotateBy ( const Rotation2d other) const
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)
Parameters
otherThe rotation to rotate by.
Returns
The new rotated Rotation2d.

◆ Sin()

constexpr double frc::Rotation2d::Sin ( ) const
inlineconstexpr

Returns the sine of the rotation.

Returns
The sine of the rotation.

◆ Tan()

constexpr double frc::Rotation2d::Tan ( ) const
inlineconstexpr

Returns the tangent of the rotation.

Returns
The tangent of the rotation.

The documentation for this class was generated from the following files: