![]() |
MoveG 1.0.0
A modern C++ library for Robotics
|
Class for representing and managing rotations in three-dimensional space. More...
#include <rotation_lib.h>
Collaboration diagram for MoveG::Rotation:Public Member Functions | |
| Rotation () | |
| Default constructor. | |
| Rotation (const Rotation &other) | |
| Copy constructor. | |
| Rotation (Rotation &&other) noexcept | |
| Move constructor for the Rotation class. | |
| Rotation (const Eigen::Matrix3d &rotation_matrix) | |
| Constructor from rotation matrix. | |
| Rotation (const Eigen::Quaterniond &quaternion) | |
| Constructor from quaternion. | |
| Rotation (const Eigen::AngleAxisd &angle_axis) | |
| Constructor from axis-angle. | |
| Rotation (double angle1, double angle2, double angle3, bool intrinsic=true, const std::string &sequence="ZYX", bool degree=false) | |
| Constructor from Euler angles. | |
| ~Rotation ()=default | |
| Default destructor. | |
| Eigen::Matrix3d | toRotationMatrix () const |
| Converts the rotation to a rotation matrix. | |
| Eigen::Quaterniond | toQuaternion () const |
| Converts the rotation to a quaternion. | |
| Eigen::AngleAxisd | toAngleAxis () const |
| Converts the rotation to an axis-angle representation. | |
| Eigen::Vector3d | toEulerAngles (bool intrinsic=true, const std::string &sequence="ZYX") const |
| Converts the rotation to Euler angles. | |
| Rotation | operator* (const Rotation &other) const |
| Composition of two rotations. | |
| Rotation & | operator= (const Rotation &other) |
| Assignment operator. | |
| Rotation & | operator= (Rotation &&other) noexcept |
| Move assignment operator. | |
Static Public Member Functions | |
| static Rotation | fromRotationMatrix (const Eigen::Matrix3d &rotation_matrix) |
| Creates a rotation from a rotation matrix. | |
| static Rotation | fromQuaternion (const Eigen::Quaterniond &quaternion) |
| Creates a rotation from a quaternion. | |
| static Rotation | fromAngleAxis (const Eigen::AngleAxisd &angle_axis) |
| Creates a rotation from an axis-angle representation. | |
| static Rotation | fromEulerAngles (double angle1, double angle2, double angle3, bool intrinsic=true, const std::string &sequence="XYZ", bool degree=false) |
| Creates a rotation from Euler angles. | |
| static double | normalizeAngle (double angle) |
| Normalizes an angle to the range [-π, π]. | |
| static double | normalizeAngleRange (double angle, double minVal, double maxVal) |
| Normalizes an angle to a specified range. | |
| static Eigen::Vector3d | normalizeEulerAngles (const Eigen::Vector3d &angles) |
| Normalizes Euler angles to the range [-π, π]. | |
| static Eigen::Quaterniond | quaternion_difference (const Eigen::Quaterniond &a, const Eigen::Quaterniond &b) |
| Calculates the difference between two quaternions. | |
| static Eigen::Quaterniond | quaternion_negation (const Eigen::Quaterniond &v) |
| Negates the quaternion. | |
| static Eigen::Quaterniond | scalar_product (const Eigen::Quaterniond &v, double t) |
| Calculates the scalar product of a quaternion by a scalar. | |
| static Eigen::Quaterniond | quaternion_minus (const Eigen::Quaterniond &v1, const Eigen::Quaterniond &v0) |
| Calculates the difference between two quaternions (v1 - v0). | |
| static Eigen::Quaterniond | quaternion_plus (const Eigen::Quaterniond &v1, const Eigen::Quaterniond &v0) |
| Calculates the sum of two quaternions. | |
| static double | deg2rad (double degree) |
| Converts degrees to radians. | |
| static double | rad2deg (double radian) |
| Converts radians to degrees. | |
| static Eigen::Matrix3d | rotationX (double angle) |
| Rotation matrix for a rotation around the X axis. | |
| static Eigen::Matrix3d | rotationY (double angle) |
| Rotation matrix for a rotation around the Y axis. | |
| static Eigen::Matrix3d | rotationZ (double angle) |
| Rotation matrix for a rotation around the Z axis. | |
| static Eigen::Matrix3d | matrixS (const Eigen::Vector3d &omega) |
| Calculates the S matrix. | |
| static Eigen::Matrix3d | matrixR_dot (const Eigen::Matrix3d &R, const Eigen::Matrix3d &S) |
| Calculates the R_dot matrix. | |
| static Eigen::Matrix3d | matrixR_dot (const Eigen::Matrix3d &R, const Eigen::Vector3d &omega) |
| Calculates the R_dot matrix from an angular velocity vector. | |
| static Eigen::Matrix3d | matrixT (const Eigen::Vector3d &angles, const std::string &sequence) |
| Calculates the T matrix. | |
Static Private Member Functions | |
| static Eigen::AngleAxisd | angleAxis (char axis, double angle) |
| Creates an axis-angle representation. | |
| static int | axisToIndex (char axis) |
| Converts an axis character to index. | |
| static int | checkSequence (const std::string &sequence) |
| Checks the validity of the Euler angle sequence. | |
Private Attributes | |
| Eigen::Quaterniond | q |
| Internal representation of rotation via quaternion. | |
Friends | |
| std::ostream & | operator<< (std::ostream &os, const Rotation &rotation) |
| Outputs the rotation to a stream in quaternion format. | |
Class for representing and managing rotations in three-dimensional space.
This class supports various rotation representations, including rotation matrices, quaternions, axis-angle, and Euler angles. It also allows composition of rotations.
Definition at line 50 of file rotation_lib.h.
| MoveG::Rotation::Rotation | ( | ) |
Default constructor.
Initializes the rotation as identity.
Definition at line 17 of file rotation_lib.cpp.
Referenced by fromAngleAxis(), fromEulerAngles(), fromQuaternion(), fromRotationMatrix(), and operator*().
Here is the caller graph for this function:| MoveG::Rotation::Rotation | ( | const Rotation & | other | ) |
Copy constructor.
| other | Another rotation to copy. |
Definition at line 22 of file rotation_lib.cpp.
|
noexcept |
Move constructor for the Rotation class.
This constructor allows the creation of a Rotation object by transferring the resources from another Rotation object. It is marked as noexcept to indicate that it does not throw exceptions.
| other | The Rotation object to be moved. |
Definition at line 27 of file rotation_lib.cpp.
| MoveG::Rotation::Rotation | ( | const Eigen::Matrix3d & | rotation_matrix | ) |
Constructor from rotation matrix.
| rotation_matrix | 3x3 rotation matrix. |
Definition at line 32 of file rotation_lib.cpp.
| MoveG::Rotation::Rotation | ( | const Eigen::Quaterniond & | quaternion | ) |
Constructor from quaternion.
| quaternion | Quaternion representing the rotation. |
Definition at line 37 of file rotation_lib.cpp.
| MoveG::Rotation::Rotation | ( | const Eigen::AngleAxisd & | angle_axis | ) |
Constructor from axis-angle.
| angle_axis | Axis-angle representation of the rotation. |
Definition at line 42 of file rotation_lib.cpp.
| MoveG::Rotation::Rotation | ( | double | angle1, |
| double | angle2, | ||
| double | angle3, | ||
| bool | intrinsic = true, |
||
| const std::string & | sequence = "ZYX", |
||
| bool | degree = false |
||
| ) |
Constructor from Euler angles.
| angle1 | First Euler angle. |
| angle2 | Second Euler angle. |
| angle3 | Third Euler angle. |
| intrinsic | If true, uses intrinsic rotations; otherwise, extrinsic. |
| sequence | Sequence of axes (e.g., "ZYX"). |
| degree | If true, angles are in degrees; otherwise, in radians. |
Definition at line 47 of file rotation_lib.cpp.
References angleAxis(), checkSequence(), deg2rad(), and q.
Here is the call graph for this function:
|
default |
Default destructor.
|
staticprivate |
Creates an axis-angle representation.
Definition at line 234 of file rotation_lib.cpp.
Referenced by Rotation().
Here is the caller graph for this function:
|
staticprivate |
Converts an axis character to index.
| axis | Rotation axis ('X', 'Y', 'Z' or lowercase). |
| std::invalid_argument | If the axis is not valid. |
Definition at line 253 of file rotation_lib.cpp.
Referenced by toEulerAngles().
Here is the caller graph for this function:
|
staticprivate |
Checks the validity of the Euler angle sequence.
| sequence | Sequence of axes (e.g., "XYZ"). |
| std::invalid_argument | If the sequence is not valid. |
Definition at line 272 of file rotation_lib.cpp.
Referenced by matrixT(), Rotation(), and toEulerAngles().
Here is the caller graph for this function:
|
static |
Converts degrees to radians.
| degree | Angle in degrees. |
Definition at line 283 of file rotation_lib.cpp.
Referenced by main(), and Rotation().
Here is the caller graph for this function:
|
static |
Creates a rotation from an axis-angle representation.
| angle_axis | Axis-angle representation of the rotation. |
Definition at line 93 of file rotation_lib.cpp.
References Rotation().
Referenced by main().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Creates a rotation from Euler angles.
| angle1 | First Euler angle. |
| angle2 | Second Euler angle. |
| angle3 | Third Euler angle. |
| intrinsic | If true, uses intrinsic rotations; otherwise, extrinsic. |
| sequence | Sequence of axes (e.g., "XYZ"). |
| degree | If true, angles are in degrees; otherwise, in radians. |
Definition at line 98 of file rotation_lib.cpp.
References Rotation().
Referenced by main().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Creates a rotation from a quaternion.
| quaternion | Quaternion representing the rotation. |
Definition at line 88 of file rotation_lib.cpp.
References Rotation().
Referenced by main().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Creates a rotation from a rotation matrix.
Static methods to define a rotation Static methods allow creating a rotation without having to instantiate an object.
Example: Rotation rot = Rotation::fromEulerAngles(0, 0, 0, true, "XYZ", false); Otherwise you would have to do:
Rotation rot; rot = rot.fromEulerAngles(0, 0, 0, true, "XYZ", false);
| rotation_matrix | 3x3 rotation matrix. |
Definition at line 83 of file rotation_lib.cpp.
References Rotation().
Here is the call graph for this function:
|
static |
Calculates the R_dot matrix.
| R | Rotation matrix. |
| S | S matrix. |
Definition at line 353 of file rotation_lib.cpp.
Referenced by main(), and matrixR_dot().
Here is the caller graph for this function:
|
static |
Calculates the R_dot matrix from an angular velocity vector.
| R | Rotation matrix. |
| omega | Angular velocity vector. |
Definition at line 358 of file rotation_lib.cpp.
References matrixR_dot(), and matrixS().
Here is the call graph for this function:
|
static |
Calculates the S matrix.
| omega | Angular velocity vector. (Different from Euler angle velocities) |
Definition at line 345 of file rotation_lib.cpp.
Referenced by main(), and matrixR_dot().
Here is the caller graph for this function:
|
static |
Calculates the T matrix.
| angles | Euler angles vector. |
| sequence | Sequence of axes (e.g., "ZYX", "ZYZ"). |
| std::runtime_error | If the matrix is singular (determinant near zero) |
Definition at line 364 of file rotation_lib.cpp.
References checkSequence(), rotationX(), rotationY(), and rotationZ().
Referenced by main().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Normalizes an angle to the range [-π, π].
| angle | Angle in radians |
Definition at line 182 of file rotation_lib.cpp.
Referenced by main(), and normalizeEulerAngles().
Here is the caller graph for this function:
|
static |
Normalizes an angle to a specified range.
| angle | Angle in radians |
| minVal | Lower bound of the range |
| maxVal | Upper bound of the range |
Definition at line 201 of file rotation_lib.cpp.
|
static |
Normalizes Euler angles to the range [-π, π].
| angles | Vector of Euler angles in radians |
Definition at line 226 of file rotation_lib.cpp.
References normalizeAngle().
Here is the call graph for this function:Composition of two rotations.
| other | Rotation to compose with. |
Definition at line 152 of file rotation_lib.cpp.
References q, and Rotation().
Here is the call graph for this function:Assignment operator.
| other | Rotation to assign. |
Definition at line 157 of file rotation_lib.cpp.
References q.
Move assignment operator.
| other | Rotation to assign. |
Definition at line 166 of file rotation_lib.cpp.
|
static |
Calculates the difference between two quaternions.
| a | Reference quaternion. |
| b | Quaternion to subtract. |
Definition at line 294 of file rotation_lib.cpp.
|
static |
Calculates the difference between two quaternions (v1 - v0).
| v1 | First quaternion. |
| v0 | Second quaternion. |
Definition at line 310 of file rotation_lib.cpp.
|
static |
Negates the quaternion.
| v | Quaternion to negate. |
Definition at line 300 of file rotation_lib.cpp.
|
static |
Calculates the sum of two quaternions.
| v1 | First quaternion. |
| v0 | Second quaternion. |
Definition at line 316 of file rotation_lib.cpp.
|
static |
Converts radians to degrees.
| radian | Angle in radians. |
Definition at line 289 of file rotation_lib.cpp.
Referenced by main(), and printEulerAngles().
Here is the caller graph for this function:
|
static |
Rotation matrix for a rotation around the X axis.
| angle | Rotation angle in radians. |
Definition at line 323 of file rotation_lib.cpp.
Referenced by main(), and matrixT().
Here is the caller graph for this function:
|
static |
Rotation matrix for a rotation around the Y axis.
| angle | Rotation angle in radians. |
Definition at line 330 of file rotation_lib.cpp.
Referenced by main(), and matrixT().
Here is the caller graph for this function:
|
static |
Rotation matrix for a rotation around the Z axis.
| angle | Rotation angle in radians. |
Definition at line 337 of file rotation_lib.cpp.
Referenced by main(), and matrixT().
Here is the caller graph for this function:
|
static |
Calculates the scalar product of a quaternion by a scalar.
| v | Quaternion to scale. |
| t | Scale to multiply by. |
Definition at line 305 of file rotation_lib.cpp.
| Eigen::AngleAxisd MoveG::Rotation::toAngleAxis | ( | ) | const |
Converts the rotation to an axis-angle representation.
Definition at line 121 of file rotation_lib.cpp.
References q.
Referenced by main().
Here is the caller graph for this function:| Eigen::Vector3d MoveG::Rotation::toEulerAngles | ( | bool | intrinsic = true, |
| const std::string & | sequence = "ZYX" |
||
| ) | const |
Converts the rotation to Euler angles.
| intrinsic | If true, uses intrinsic rotations; otherwise, extrinsic. |
| sequence | Sequence of axes (e.g., "ZYX"). |
Definition at line 127 of file rotation_lib.cpp.
References axisToIndex(), checkSequence(), and q.
Referenced by main().
Here is the call graph for this function:
Here is the caller graph for this function:| Eigen::Quaterniond MoveG::Rotation::toQuaternion | ( | ) | const |
Converts the rotation to a quaternion.
Definition at line 115 of file rotation_lib.cpp.
References q.
Referenced by main().
Here is the caller graph for this function:| Eigen::Matrix3d MoveG::Rotation::toRotationMatrix | ( | ) | const |
Converts the rotation to a rotation matrix.
Definition at line 109 of file rotation_lib.cpp.
References q.
Referenced by main().
Here is the caller graph for this function:
|
friend |
Outputs the rotation to a stream in quaternion format.
| os | Stream to output to. |
| rotation | Rotation to output. |
Definition at line 173 of file rotation_lib.cpp.
|
private |
Internal representation of rotation via quaternion.
Definition at line 370 of file rotation_lib.h.
Referenced by operator*(), operator=(), Rotation(), toAngleAxis(), toEulerAngles(), toQuaternion(), and toRotationMatrix().