30{
31 std::cout << "==============================================" << std::endl;
32 std::cout << "MoveG Rotation Library Example Usage" << std::endl;
33 std::cout << "==============================================" << std::endl;
34
35
36 std::cout << "\n1. Creating rotations using different constructors:" << std::endl;
37
38
40 std::cout <<
"Identity rotation matrix:\n" << identity.
toRotationMatrix() << std::endl;
41
42
46
47 Rotation rot_euler(yaw, pitch, roll,
true,
"ZYX",
false);
48 std::cout << "Rotation from Euler angles (ZYX, intrinsic):\n"
49 << rot_euler.toRotationMatrix() << std::endl;
50
51
52 Eigen::Matrix3d R = Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitZ()).toRotationMatrix();
54 std::cout << "Rotation from matrix (45° around Z):\n"
55 << rot_matrix.toRotationMatrix() << std::endl;
56
57
58 Eigen::Quaterniond q =
59 Eigen::Quaterniond(Eigen::AngleAxisd(M_PI / 3, Eigen::Vector3d::UnitY()));
61 std::cout << "Rotation from quaternion (60° around Y):\n"
62 << rot_quat.toRotationMatrix() << std::endl;
63
64
65 Eigen::AngleAxisd aa(M_PI / 6, Eigen::Vector3d::UnitX());
67 std::cout << "Rotation from angle-axis (30° around X):\n"
68 << rot_aa.toRotationMatrix() << std::endl;
69
70
71 std::cout << "\n2. Using static methods to create rotations:" << std::endl;
72
74 std::cout << "Static method Euler angles rotation:\n"
76
78 std::cout << "Static method quaternion rotation:\n"
80
81
82 std::cout << "\n3. Converting between different rotation representations:" << std::endl;
83
84
85 Rotation rot_convert(M_PI / 4, M_PI / 6, M_PI / 3,
true,
"ZYX",
false);
86
87
88 Eigen::Matrix3d rot_mat = rot_convert.toRotationMatrix();
89 Eigen::Quaterniond rot_q = rot_convert.toQuaternion();
90 Eigen::AngleAxisd rot_aa_convert = rot_convert.toAngleAxis();
91 Eigen::Vector3d rot_euler_angles = rot_convert.toEulerAngles(true, "ZYX");
92
93 std::cout << "Original rotation from Euler angles (ZYX):" << std::endl;
94 printEulerAngles(Eigen::Vector3d(M_PI / 4, M_PI / 6, M_PI / 3),
"Input angles",
"ZYX");
95
96 std::cout << "\nAs a rotation matrix:\n" << rot_mat << std::endl;
97
99
101 << "° around axis [" << rot_aa_convert.axis().x() << ", " << rot_aa_convert.axis().y()
102 << ", " << rot_aa_convert.axis().z() << "]" << std::endl;
103
105
106
107 std::cout << "\n4. Composition of rotations:" << std::endl;
108
109
112
113
114 Rotation rot_combined = rot1 * rot2;
115
116 std::cout <<
"Rotation 1 (90° around Z):\n" << rot1.
toRotationMatrix() << std::endl;
117 std::cout <<
"Rotation 2 (90° around Y):\n" << rot2.
toRotationMatrix() << std::endl;
118 std::cout << "Combined rotation (rot1 * rot2):\n"
120
121
122 Rotation rot_combined2 = rot2 * rot1;
123 std::cout << "Different order (rot2 * rot1):\n"
125
126
127 std::cout << "\n5. Utility functions:" << std::endl;
128
129
130 double angle_deg = 45.0;
132 std::cout << angle_deg << "° = " << angle_rad << " radians" << std::endl;
133 std::cout << angle_rad <<
" radians = " <<
Rotation::rad2deg(angle_rad) <<
"°" << std::endl;
134
135
136 double big_angle = 5 * M_PI;
138 std::cout << "Normalizing " << big_angle << " radians to [-π, π]: " << normalized
140
141
142 std::cout << "\nElementary rotation matrices:" << std::endl;
146
147
148 Eigen::Vector3d omega(0.1, 0.2, 0.3);
149 std::cout << "\nMatrix S for angular velocity [0.1, 0.2, 0.3]:\n"
151
152 Eigen::Matrix3d R_current = Eigen::Matrix3d::Identity();
154 std::cout << "Matrix R_dot:\n" << R_dot << std::endl;
155
156
157 try
158 {
159 Eigen::Vector3d angles_for_T(M_PI / 4, M_PI / 6, M_PI / 3);
161 std::cout <<
"\nMatrix T for ZYX Euler angles [" <<
Rotation::rad2deg(angles_for_T[0])
164 << T << std::endl;
165 }
166 catch (const std::exception &e)
167 {
168 std::cerr << "Error calculating matrix T: " << e.what() << std::endl;
169 }
170
171 std::cout << "==============================================" << std::endl;
172
173 return 0;
174}
Class for representing and managing rotations in three-dimensional space.
static double normalizeAngle(double angle)
Normalizes an angle to the range [-π, π].
static Eigen::Matrix3d matrixT(const Eigen::Vector3d &angles, const std::string &sequence)
Calculates the T matrix.
Eigen::Matrix3d toRotationMatrix() const
Converts the rotation to a rotation matrix.
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 Rotation fromQuaternion(const Eigen::Quaterniond &quaternion)
Creates a rotation from a quaternion.
static Eigen::Matrix3d rotationY(double angle)
Rotation matrix for a rotation around the Y axis.
static double deg2rad(double degree)
Converts degrees to radians.
static double rad2deg(double radian)
Converts radians to degrees.
static Eigen::Matrix3d matrixS(const Eigen::Vector3d &omega)
Calculates the S matrix.
static Eigen::Matrix3d rotationZ(double angle)
Rotation matrix for a rotation around the Z axis.
static Eigen::Matrix3d rotationX(double angle)
Rotation matrix for a rotation around the X axis.
static Eigen::Matrix3d matrixR_dot(const Eigen::Matrix3d &R, const Eigen::Matrix3d &S)
Calculates the R_dot matrix.
void printQuaternion(const Eigen::Quaterniond &quat, const std::string &description)
void printEulerAngles(const Eigen::Vector3d &angles, const std::string &description, const std::string &sequence)