WPILibC++ 2024.3.2
frc::Rotation3d Class Reference

A rotation in a 3D coordinate frame represented by a quaternion. More...

#include <frc/geometry/Rotation3d.h>

Public Member Functions

 Rotation3d ()=default
 Constructs a Rotation3d with a default angle of 0 degrees. More...
 
 Rotation3d (const Quaternion &q)
 Constructs a Rotation3d from a quaternion. More...
 
 Rotation3d (units::radian_t roll, units::radian_t pitch, units::radian_t yaw)
 Constructs a Rotation3d from extrinsic roll, pitch, and yaw. More...
 
 Rotation3d (const Eigen::Vector3d &axis, units::radian_t angle)
 Constructs a Rotation3d with the given axis-angle representation. More...
 
 Rotation3d (const Eigen::Vector3d &rvec)
 Constructs a Rotation3d with the given rotation vector representation. More...
 
 Rotation3d (const Eigen::Matrix3d &rotationMatrix)
 Constructs a Rotation3d from a rotation matrix. More...
 
 Rotation3d (const Eigen::Vector3d &initial, const Eigen::Vector3d &final)
 Constructs a Rotation3d that rotates the initial vector onto the final vector. More...
 
Rotation3d operator+ (const Rotation3d &other) const
 Adds two rotations together. More...
 
Rotation3d operator- (const Rotation3d &other) const
 Subtracts the new rotation from the current rotation and returns the new rotation. More...
 
Rotation3d operator- () const
 Takes the inverse of the current rotation. More...
 
Rotation3d operator* (double scalar) const
 Multiplies the current rotation by a scalar. More...
 
Rotation3d operator/ (double scalar) const
 Divides the current rotation by a scalar. More...
 
bool operator== (const Rotation3d &) const
 Checks equality between this Rotation3d and another object. More...
 
Rotation3d RotateBy (const Rotation3d &other) const
 Adds the new rotation to the current rotation. More...
 
const QuaternionGetQuaternion () const
 Returns the quaternion representation of the Rotation3d. More...
 
units::radian_t X () const
 Returns the counterclockwise rotation angle around the X axis (roll). More...
 
units::radian_t Y () const
 Returns the counterclockwise rotation angle around the Y axis (pitch). More...
 
units::radian_t Z () const
 Returns the counterclockwise rotation angle around the Z axis (yaw). More...
 
Eigen::Vector3d Axis () const
 Returns the axis in the axis-angle representation of this rotation. More...
 
units::radian_t Angle () const
 Returns the angle in the axis-angle representation of this rotation. More...
 
Rotation2d ToRotation2d () const
 Returns a Rotation2d representing this Rotation3d projected into the X-Y plane. More...
 

Detailed Description

A rotation in a 3D coordinate frame represented by a quaternion.

Constructor & Destructor Documentation

◆ Rotation3d() [1/7]

frc::Rotation3d::Rotation3d ( )
default

Constructs a Rotation3d with a default angle of 0 degrees.

◆ Rotation3d() [2/7]

frc::Rotation3d::Rotation3d ( const Quaternion q)
explicit

Constructs a Rotation3d from a quaternion.

Parameters
qThe quaternion.

◆ Rotation3d() [3/7]

frc::Rotation3d::Rotation3d ( units::radian_t  roll,
units::radian_t  pitch,
units::radian_t  yaw 
)

Constructs a Rotation3d from extrinsic roll, pitch, and yaw.

Extrinsic rotations occur in that order around the axes in the fixed global frame rather than the body frame.

Angles are measured counterclockwise with the rotation axis pointing "out of the page". If you point your right thumb along the positive axis direction, your fingers curl in the direction of positive rotation.

Parameters
rollThe counterclockwise rotation angle around the X axis (roll).
pitchThe counterclockwise rotation angle around the Y axis (pitch).
yawThe counterclockwise rotation angle around the Z axis (yaw).

◆ Rotation3d() [4/7]

frc::Rotation3d::Rotation3d ( const Eigen::Vector3d &  axis,
units::radian_t  angle 
)

Constructs a Rotation3d with the given axis-angle representation.

The axis doesn't have to be normalized.

Parameters
axisThe rotation axis.
angleThe rotation around the axis.

◆ Rotation3d() [5/7]

frc::Rotation3d::Rotation3d ( const Eigen::Vector3d &  rvec)
explicit

Constructs a Rotation3d with the given rotation vector representation.

This representation is equivalent to axis-angle, where the normalized axis is multiplied by the rotation around the axis in radians.

Parameters
rvecThe rotation vector.

◆ Rotation3d() [6/7]

frc::Rotation3d::Rotation3d ( const Eigen::Matrix3d &  rotationMatrix)
explicit

Constructs a Rotation3d from a rotation matrix.

Parameters
rotationMatrixThe rotation matrix.
Exceptions
std::domain_errorif the rotation matrix isn't special orthogonal.

◆ Rotation3d() [7/7]

frc::Rotation3d::Rotation3d ( const Eigen::Vector3d &  initial,
const Eigen::Vector3d &  final 
)

Constructs a Rotation3d that rotates the initial vector onto the final vector.

This is useful for turning a 3D vector (final) into an orientation relative to a coordinate system vector (initial).

Parameters
initialThe initial vector.
finalThe final vector.

Member Function Documentation

◆ Angle()

units::radian_t frc::Rotation3d::Angle ( ) const

Returns the angle in the axis-angle representation of this rotation.

◆ Axis()

Eigen::Vector3d frc::Rotation3d::Axis ( ) const

Returns the axis in the axis-angle representation of this rotation.

◆ GetQuaternion()

const Quaternion & frc::Rotation3d::GetQuaternion ( ) const

Returns the quaternion representation of the Rotation3d.

◆ operator*()

Rotation3d frc::Rotation3d::operator* ( double  scalar) const

Multiplies the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation3d.

◆ operator+()

Rotation3d frc::Rotation3d::operator+ ( const Rotation3d other) const

Adds two rotations together.

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

◆ operator-() [1/2]

Rotation3d frc::Rotation3d::operator- ( ) const

Takes the inverse of the current rotation.

Returns
The inverse of the current rotation.

◆ operator-() [2/2]

Rotation3d frc::Rotation3d::operator- ( const Rotation3d other) const

Subtracts the new rotation from the current rotation and returns the new rotation.

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

◆ operator/()

Rotation3d frc::Rotation3d::operator/ ( double  scalar) const

Divides the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation3d.

◆ operator==()

bool frc::Rotation3d::operator== ( const Rotation3d ) const

Checks equality between this Rotation3d and another object.

◆ RotateBy()

Rotation3d frc::Rotation3d::RotateBy ( const Rotation3d other) const

Adds the new rotation to the current rotation.

The other rotation is applied extrinsically, which means that it rotates around the global axes. For example, Rotation3d{90_deg, 0, 0}.RotateBy(Rotation3d{0, 45_deg, 0}) rotates by 90 degrees around the +X axis and then by 45 degrees around the global +Y axis. (This is equivalent to Rotation3d{90_deg, 45_deg, 0})

Parameters
otherThe extrinsic rotation to rotate by.
Returns
The new rotated Rotation3d.

◆ ToRotation2d()

Rotation2d frc::Rotation3d::ToRotation2d ( ) const

Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.

◆ X()

units::radian_t frc::Rotation3d::X ( ) const

Returns the counterclockwise rotation angle around the X axis (roll).

◆ Y()

units::radian_t frc::Rotation3d::Y ( ) const

Returns the counterclockwise rotation angle around the Y axis (pitch).

◆ Z()

units::radian_t frc::Rotation3d::Z ( ) const

Returns the counterclockwise rotation angle around the Z axis (yaw).


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