A rotation in a 3D coordinate frame represented by a quaternion. More...
#include <frc/geometry/Rotation3d.h>
Public Member Functions | |
constexpr | Rotation3d ()=default |
Constructs a Rotation3d representing no rotation. | |
constexpr | Rotation3d (const Quaternion &q) |
Constructs a Rotation3d from a quaternion. | |
constexpr | Rotation3d (units::radian_t roll, units::radian_t pitch, units::radian_t yaw) |
Constructs a Rotation3d from extrinsic roll, pitch, and yaw. | |
constexpr | Rotation3d (const Eigen::Vector3d &axis, units::radian_t angle) |
Constructs a Rotation3d with the given axis-angle representation. | |
constexpr | Rotation3d (const Eigen::Vector3d &rvec) |
Constructs a Rotation3d with the given rotation vector representation. | |
constexpr | Rotation3d (const Eigen::Matrix3d &rotationMatrix) |
Constructs a Rotation3d from a rotation matrix. | |
constexpr | Rotation3d (const Eigen::Vector3d &initial, const Eigen::Vector3d &final) |
Constructs a Rotation3d that rotates the initial vector onto the final vector. | |
constexpr | Rotation3d (const Rotation2d &rotation) |
Constructs a 3D rotation from a 2D rotation in the X-Y plane. | |
constexpr Rotation3d | operator+ (const Rotation3d &other) const |
Adds two rotations together. | |
constexpr Rotation3d | operator- (const Rotation3d &other) const |
Subtracts the new rotation from the current rotation and returns the new rotation. | |
constexpr Rotation3d | operator- () const |
Takes the inverse of the current rotation. | |
constexpr Rotation3d | operator* (double scalar) const |
Multiplies the current rotation by a scalar. | |
constexpr Rotation3d | operator/ (double scalar) const |
Divides the current rotation by a scalar. | |
constexpr bool | operator== (const Rotation3d &other) const |
Checks equality between this Rotation3d and another object. | |
constexpr Rotation3d | RotateBy (const Rotation3d &other) const |
Adds the new rotation to the current rotation. | |
constexpr const Quaternion & | GetQuaternion () const |
Returns the quaternion representation of the Rotation3d. | |
constexpr units::radian_t | X () const |
Returns the counterclockwise rotation angle around the X axis (roll). | |
constexpr units::radian_t | Y () const |
Returns the counterclockwise rotation angle around the Y axis (pitch). | |
constexpr units::radian_t | Z () const |
Returns the counterclockwise rotation angle around the Z axis (yaw). | |
constexpr Eigen::Vector3d | Axis () const |
Returns the axis in the axis-angle representation of this rotation. | |
constexpr units::radian_t | Angle () const |
Returns the angle in the axis-angle representation of this rotation. | |
constexpr Eigen::Matrix3d | ToMatrix () const |
Returns rotation matrix representation of this rotation. | |
constexpr Eigen::Vector3d | ToVector () const |
Returns rotation vector representation of this rotation. | |
constexpr Rotation2d | ToRotation2d () const |
Returns a Rotation2d representing this Rotation3d projected into the X-Y plane. | |
A rotation in a 3D coordinate frame represented by a quaternion.
|
constexprdefault |
Constructs a Rotation3d representing no rotation.
|
inlineexplicitconstexpr |
Constructs a Rotation3d from a quaternion.
q | The quaternion. |
|
inlineconstexpr |
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.
roll | The counterclockwise rotation angle around the X axis (roll). |
pitch | The counterclockwise rotation angle around the Y axis (pitch). |
yaw | The counterclockwise rotation angle around the Z axis (yaw). |
|
inlineconstexpr |
Constructs a Rotation3d with the given axis-angle representation.
The axis doesn't have to be normalized.
axis | The rotation axis. |
angle | The rotation around the axis. |
|
inlineexplicitconstexpr |
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.
rvec | The rotation vector. |
|
inlineexplicitconstexpr |
Constructs a Rotation3d from a rotation matrix.
rotationMatrix | The rotation matrix. |
|
inlineconstexpr |
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).
initial | The initial vector. |
final | The final vector. |
|
inlineexplicitconstexpr |
Constructs a 3D rotation from a 2D rotation in the X-Y plane.
rotation | The 2D rotation. |
|
inlineconstexpr |
Returns the angle in the axis-angle representation of this rotation.
|
inlineconstexpr |
Returns the axis in the axis-angle representation of this rotation.
|
inlineconstexpr |
Returns the quaternion representation of the Rotation3d.
|
inlineconstexpr |
Multiplies the current rotation by a scalar.
scalar | The scalar. |
|
inlineconstexpr |
Adds two rotations together.
other | The rotation to add. |
|
inlineconstexpr |
Takes the inverse of the current rotation.
|
inlineconstexpr |
Subtracts the new rotation from the current rotation and returns the new rotation.
other | The rotation to subtract. |
|
inlineconstexpr |
Divides the current rotation by a scalar.
scalar | The scalar. |
|
inlineconstexpr |
Checks equality between this Rotation3d and another object.
|
inlineconstexpr |
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})
other | The extrinsic rotation to rotate by. |
|
inlineconstexpr |
Returns rotation matrix representation of this rotation.
|
inlineconstexpr |
Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
|
inlineconstexpr |
Returns rotation vector representation of this rotation.
|
inlineconstexpr |
Returns the counterclockwise rotation angle around the X axis (roll).
|
inlineconstexpr |
Returns the counterclockwise rotation angle around the Y axis (pitch).
|
inlineconstexpr |
Returns the counterclockwise rotation angle around the Z axis (yaw).