WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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.
 
constexpr Rotation2d (units::angle_unit auto value)
 Constructs a Rotation2d with the given angle.
 
constexpr Rotation2d (double x, double y)
 Constructs a Rotation2d with the given x and y (cosine and sine) components.
 
constexpr Rotation2d (const Eigen::Matrix2d &rotationMatrix)
 Constructs a Rotation2d from a rotation matrix.
 
constexpr Rotation2d operator+ (const Rotation2d &other) const
 Adds two rotations together, with the result being bounded between -π and π.
 
constexpr Rotation2d operator- (const Rotation2d &other) const
 Subtracts the new rotation from the current rotation and returns the new rotation.
 
constexpr Rotation2d operator- () const
 Takes the inverse of the current rotation.
 
constexpr Rotation2d operator* (double scalar) const
 Multiplies the current rotation by a scalar.
 
constexpr Rotation2d operator/ (double scalar) const
 Divides the current rotation by a scalar.
 
constexpr bool operator== (const Rotation2d &other) const
 Checks equality between this Rotation2d and another object.
 
constexpr Rotation2d RotateBy (const Rotation2d &other) const
 Adds the new rotation to the current rotation using a rotation matrix.
 
constexpr Eigen::Matrix2d ToMatrix () const
 Returns matrix representation of this rotation.
 
constexpr units::radian_t Radians () const
 Returns the radian value of the rotation.
 
constexpr units::degree_t Degrees () const
 Returns the degree value of the rotation.
 
constexpr double Cos () const
 Returns the cosine of the rotation.
 
constexpr double Sin () const
 Returns the sine of the rotation.
 
constexpr double Tan () const
 Returns the tangent of the rotation.
 

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]

frc::Rotation2d::Rotation2d ( )
constexprdefault

Constructs a Rotation2d with a default angle of 0 degrees.

◆ Rotation2d() [2/4]

frc::Rotation2d::Rotation2d ( units::angle_unit auto value)
inlineconstexpr

Constructs a Rotation2d with the given angle.

Parameters
valueThe value of the angle.

◆ Rotation2d() [3/4]

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

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.

◆ Rotation2d() [4/4]

frc::Rotation2d::Rotation2d ( const Eigen::Matrix2d & rotationMatrix)
inlineexplicitconstexpr

Constructs a Rotation2d from a rotation matrix.

Parameters
rotationMatrixThe rotation matrix.
Throws:
std::domain_error if the rotation matrix isn't special orthogonal.

Member Function Documentation

◆ Cos()

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

Returns the cosine of the rotation.

Returns
The cosine of the rotation.

◆ Degrees()

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*()

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

Multiplies the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation2d.

◆ operator+()

Rotation2d frc::Rotation2d::operator+ ( const Rotation2d & other) const
inlineconstexpr

Adds two rotations together, with the result being bounded between -π and π.

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]

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

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]

Rotation2d frc::Rotation2d::operator- ( const Rotation2d & other) const
inlineconstexpr

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/()

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

Divides the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation2d.

◆ operator==()

bool frc::Rotation2d::operator== ( const Rotation2d & other) const
inlineconstexpr

Checks equality between this Rotation2d and another object.

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

◆ Radians()

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 (-π, π]

◆ RotateBy()

Rotation2d frc::Rotation2d::RotateBy ( const Rotation2d & other) const
inlineconstexpr

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()

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

Returns the sine of the rotation.

Returns
The sine of the rotation.

◆ Tan()

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

Returns the tangent of the rotation.

Returns
The tangent of the rotation.

◆ ToMatrix()

Eigen::Matrix2d frc::Rotation2d::ToMatrix ( ) const
inlineconstexpr

Returns matrix representation of this rotation.


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