Rotation¶
-
template<IsFloatingPoint T>
class Rotation¶ Represents a 3D rotation using a 3x3 matrix, with various construction and conversion utilities.
Provides static methods for constructing rotations from matrices, quaternions, axis-angle, Euler angles, and basis vectors. Supports conversion to/from quaternions, matrix, and axis representations, as well as composition and application to vectors.
- Template Parameters:
T – Floating point type (float or double)
Public Functions
-
Rotation() = default¶
-
template<IsFloatingPoint U>
explicit operator Rotation<U>() const¶ Convert this Rotation to another floating point type.
- Template Parameters:
U – Target floating point type
- Returns:
-
std::string to_string() const¶
Get a string representation of the rotation matrix.
- Returns:
std::string String representation
-
Quaternion<T> local_to_parent_quaternion() const¶
Get the local-to-parent rotation as a Hamilton quaternion.
- Returns:
Quaternion<T> Hamilton quaternion
-
ShusterQuaternion<T> local_to_parent_shuster_quaternion() const¶
Get the local-to-parent rotation as a Shuster quaternion.
- Returns:
ShusterQuaternion<T> Shuster quaternion
-
Quaternion<T> parent_to_local_quaternion() const¶
Get the parent-to-local rotation as a Hamilton quaternion.
- Returns:
Quaternion<T> Hamilton quaternion
-
ShusterQuaternion<T> parent_to_local_shuster_quaternion() const¶
Get the parent-to-local rotation as a Shuster quaternion.
- Returns:
ShusterQuaternion<T> Shuster quaternion
-
Vec3<T> x_axis() const¶
Get the X axis of the rotation (first column of the matrix).
- Returns:
Vec3<T> X axis vector
-
Vec3<T> y_axis() const¶
Get the Y axis of the rotation (second column of the matrix).
- Returns:
Vec3<T> Y axis vector
-
Vec3<T> z_axis() const¶
Get the Z axis of the rotation (third column of the matrix).
- Returns:
Vec3<T> Z axis vector
-
Rotation operator*(const Rotation &b) const¶
Compose two rotations (this * b).
- Parameters:
b – Other rotation
- Returns:
Rotation<T> Composed rotation
Public Static Functions
-
static Rotation from_local_to_parent(Mat3<T> matrix)¶
Construct a Rotation from a local-to-parent rotation matrix.
- Parameters:
matrix – 3x3 rotation matrix
- Returns:
Rotation<T> Rotation object
-
static Rotation from_local_to_parent(Quaternion<T> quaternion)¶
Construct a Rotation from a local-to-parent quaternion.
- Parameters:
quaternion – Hamilton quaternion
- Returns:
Rotation<T> Rotation object
-
static Rotation from_local_to_parent(ShusterQuaternion<T> shuster_quaternion)¶
Construct a Rotation from a local-to-parent Shuster quaternion.
- Parameters:
shuster_quaternion – Shuster quaternion
- Returns:
Rotation<T> Rotation object
-
static Rotation from_local_to_parent(Vec3<T> axis, units::Radian angle)¶
Construct a Rotation from an axis and angle (Rodrigues’ formula).
-
static Rotation from_parent_to_local(Mat3<T> matrix)¶
Construct a Rotation from a parent-to-local rotation matrix.
- Parameters:
matrix – 3x3 rotation matrix
- Returns:
Rotation<T> Rotation object
-
static Rotation from_parent_to_local(Quaternion<T> quaternion)¶
Construct a Rotation from a parent-to-local quaternion.
- Parameters:
quaternion – Hamilton quaternion
- Returns:
Rotation<T> Rotation object
-
static Rotation from_parent_to_local(ShusterQuaternion<T> shuster_quaternion)¶
Construct a Rotation from a parent-to-local Shuster quaternion.
- Parameters:
shuster_quaternion – Shuster quaternion
- Returns:
Rotation<T> Rotation object
-
static Rotation from_parent_to_local(Vec3<T> axis, units::Radian angle)¶
Construct a Rotation from a parent-to-local axis and angle.
-
static Rotation extrinsic_euler_angles(units::Radian angle1, units::Radian angle2, units::Radian angle3, std::string sequence = "XYZ")¶
Construct a Rotation from extrinsic Euler angles.
- Parameters:
angle1 – First rotation angle (radians)
angle2 – Second rotation angle (radians)
angle3 – Third rotation angle (radians)
sequence – Axis sequence (e.g., “XYZ”)
- Returns:
Rotation<T> Rotation object
-
static Rotation intrinsic_euler_angles(units::Radian angle1, units::Radian angle2, units::Radian angle3, std::string sequence = "XYZ")¶
Construct a Rotation from intrinsic Euler angles.
- Parameters:
angle1 – First rotation angle (radians)
angle2 – Second rotation angle (radians)
angle3 – Third rotation angle (radians)
sequence – Axis sequence (e.g., “XYZ”)
- Returns:
Rotation<T> Rotation object
-
static Rotation from_basis_vectors(Vec3<T> x_axis, Vec3<T> y_axis, Vec3<T> z_axis)¶
Construct a Rotation from three basis vectors.
- Parameters:
x_axis – X axis vector
y_axis – Y axis vector
z_axis – Z axis vector
- Returns:
Rotation<T> Rotation object
-
static Mat3<T> local_to_parent_x(units::Radian angle)¶
Get a rotation matrix for a rotation about the X axis.
-
static Mat3<T> local_to_parent_y(units::Radian angle)¶
Get a rotation matrix for a rotation about the Y axis.
-
static Mat3<T> local_to_parent_z(units::Radian angle)¶
Get a rotation matrix for a rotation about the Z axis.
-
static Mat3<T> parent_to_local_x(units::Radian angle)¶
Get a parent-to-local rotation matrix about the X axis.