MoveG 1.0.0
A modern C++ library for Robotics
Loading...
Searching...
No Matches
MoveG::Rotation Class Reference

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.
 
Rotationoperator= (const Rotation &other)
 Assignment operator.
 
Rotationoperator= (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.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ Rotation() [1/7]

MoveG::Rotation::Rotation ( )

Default constructor.

Initializes the rotation as identity.

Definition at line 17 of file rotation_lib.cpp.

17 : q(Eigen::Quaterniond::Identity())
18{
19}
Eigen::Quaterniond q
Internal representation of rotation via quaternion.

Referenced by fromAngleAxis(), fromEulerAngles(), fromQuaternion(), fromRotationMatrix(), and operator*().

+ Here is the caller graph for this function:

◆ Rotation() [2/7]

MoveG::Rotation::Rotation ( const Rotation other)

Copy constructor.

Parameters
otherAnother rotation to copy.

Definition at line 22 of file rotation_lib.cpp.

22 : q(other.q)
23{
24}

◆ Rotation() [3/7]

MoveG::Rotation::Rotation ( Rotation &&  other)
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.

Parameters
otherThe Rotation object to be moved.

Definition at line 27 of file rotation_lib.cpp.

27 : q(std::move(other.q))
28{
29}

◆ Rotation() [4/7]

MoveG::Rotation::Rotation ( const Eigen::Matrix3d &  rotation_matrix)

Constructor from rotation matrix.

Parameters
rotation_matrix3x3 rotation matrix.

Definition at line 32 of file rotation_lib.cpp.

32 : q(Eigen::Quaterniond(rotation_matrix))
33{
34}

◆ Rotation() [5/7]

MoveG::Rotation::Rotation ( const Eigen::Quaterniond &  quaternion)

Constructor from quaternion.

Parameters
quaternionQuaternion representing the rotation.

Definition at line 37 of file rotation_lib.cpp.

37 : q(quaternion.normalized())
38{
39}

◆ Rotation() [6/7]

MoveG::Rotation::Rotation ( const Eigen::AngleAxisd &  angle_axis)

Constructor from axis-angle.

Parameters
angle_axisAxis-angle representation of the rotation.

Definition at line 42 of file rotation_lib.cpp.

42 : q(Eigen::Quaterniond(angle_axis))
43{
44}

◆ Rotation() [7/7]

MoveG::Rotation::Rotation ( double  angle1,
double  angle2,
double  angle3,
bool  intrinsic = true,
const std::string &  sequence = "ZYX",
bool  degree = false 
)

Constructor from Euler angles.

Parameters
angle1First Euler angle.
angle2Second Euler angle.
angle3Third Euler angle.
intrinsicIf true, uses intrinsic rotations; otherwise, extrinsic.
sequenceSequence of axes (e.g., "ZYX").
degreeIf true, angles are in degrees; otherwise, in radians.

Definition at line 47 of file rotation_lib.cpp.

53 : q(Eigen::Quaterniond::Identity())
54{
55 checkSequence(sequence);
56
57 if (degree)
58 {
59 angle1 = deg2rad(angle1);
60 angle2 = deg2rad(angle2);
61 angle3 = deg2rad(angle3);
62 }
63
64 const Eigen::AngleAxisd aa1 = angleAxis(sequence[0], angle1);
65 const Eigen::AngleAxisd aa2 = angleAxis(sequence[1], angle2);
66 const Eigen::AngleAxisd aa3 = angleAxis(sequence[2], angle3);
67
68 if (intrinsic)
69 {
70 // For intrinsic rotations, multiply in the order q3 * q2 * q1
71 q = Eigen::Quaterniond(aa3) * Eigen::Quaterniond(aa2) * Eigen::Quaterniond(aa1);
72 }
73 else
74 {
75 // For extrinsic rotations, multiply in the order q1 * q2 * q3
76 q = Eigen::Quaterniond(aa1) * Eigen::Quaterniond(aa2) * Eigen::Quaterniond(aa3);
77 }
78
79 q.normalize();
80}
static double deg2rad(double degree)
Converts degrees to radians.
static int checkSequence(const std::string &sequence)
Checks the validity of the Euler angle sequence.
static Eigen::AngleAxisd angleAxis(char axis, double angle)
Creates an axis-angle representation.

References angleAxis(), checkSequence(), deg2rad(), and q.

+ Here is the call graph for this function:

◆ ~Rotation()

MoveG::Rotation::~Rotation ( )
default

Default destructor.

Member Function Documentation

◆ angleAxis()

Eigen::AngleAxisd MoveG::Rotation::angleAxis ( char  axis,
double  angle 
)
staticprivate

Creates an axis-angle representation.

Parameters
axisRotation axis ('X', 'Y', 'Z' or lowercase).
angleRotation angle in radians.
Returns
Axis-angle representation.

Definition at line 234 of file rotation_lib.cpp.

235{
236 switch (axis)
237 {
238 case 'X':
239 case 'x':
240 return Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitX());
241 case 'Y':
242 case 'y':
243 return Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitY());
244 case 'Z':
245 case 'z':
246 return Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitZ());
247 default:
248 throw std::invalid_argument("Invalid axis. Valid axes are 'X', 'Y', or 'Z'.");
249 }
250}

Referenced by Rotation().

+ Here is the caller graph for this function:

◆ axisToIndex()

int MoveG::Rotation::axisToIndex ( char  axis)
staticprivate

Converts an axis character to index.

Parameters
axisRotation axis ('X', 'Y', 'Z' or lowercase).
Returns
Index corresponding to the axis (0 for X, 1 for Y, 2 for Z).
Exceptions
std::invalid_argumentIf the axis is not valid.

Definition at line 253 of file rotation_lib.cpp.

254{
255 switch (axis)
256 {
257 case 'X':
258 case 'x':
259 return 0;
260 case 'Y':
261 case 'y':
262 return 1;
263 case 'Z':
264 case 'z':
265 return 2;
266 default:
267 throw std::invalid_argument("Invalid axis. Valid axes are 'X', 'Y', or 'Z'.");
268 }
269}

Referenced by toEulerAngles().

+ Here is the caller graph for this function:

◆ checkSequence()

int MoveG::Rotation::checkSequence ( const std::string &  sequence)
staticprivate

Checks the validity of the Euler angle sequence.

Parameters
sequenceSequence of axes (e.g., "XYZ").
Returns
Integer value (always 1 if valid).
Exceptions
std::invalid_argumentIf the sequence is not valid.

Definition at line 272 of file rotation_lib.cpp.

273{
274 if (sequence.length() != 3 || sequence.find_first_not_of("XYZxyz") != std::string::npos)
275 {
276 throw std::invalid_argument("The axis sequence must be a string of three characters "
277 "from 'X', 'Y', and 'Z' or 'x', 'y', and 'z'.");
278 }
279 return 1;
280}

Referenced by matrixT(), Rotation(), and toEulerAngles().

+ Here is the caller graph for this function:

◆ deg2rad()

double MoveG::Rotation::deg2rad ( double  degree)
static

Converts degrees to radians.

Parameters
degreeAngle in degrees.
Returns
Angle in radians.

Definition at line 283 of file rotation_lib.cpp.

284{
285 return degree * M_PI / 180.0;
286}

Referenced by main(), and Rotation().

+ Here is the caller graph for this function:

◆ fromAngleAxis()

Rotation MoveG::Rotation::fromAngleAxis ( const Eigen::AngleAxisd &  angle_axis)
static

Creates a rotation from an axis-angle representation.

Parameters
angle_axisAxis-angle representation of the rotation.
Returns
Rotation object.

Definition at line 93 of file rotation_lib.cpp.

94{
95 return Rotation(angle_axis);
96}
Rotation()
Default constructor.

References Rotation().

Referenced by main().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ fromEulerAngles()

Rotation MoveG::Rotation::fromEulerAngles ( double  angle1,
double  angle2,
double  angle3,
bool  intrinsic = true,
const std::string &  sequence = "XYZ",
bool  degree = false 
)
static

Creates a rotation from Euler angles.

Parameters
angle1First Euler angle.
angle2Second Euler angle.
angle3Third Euler angle.
intrinsicIf true, uses intrinsic rotations; otherwise, extrinsic.
sequenceSequence of axes (e.g., "XYZ").
degreeIf true, angles are in degrees; otherwise, in radians.
Returns
Rotation object.

Definition at line 98 of file rotation_lib.cpp.

104{
105 return Rotation(angle1, angle2, angle3, intrinsic, sequence, degree);
106}

References Rotation().

Referenced by main().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ fromQuaternion()

Rotation MoveG::Rotation::fromQuaternion ( const Eigen::Quaterniond &  quaternion)
static

Creates a rotation from a quaternion.

Parameters
quaternionQuaternion representing the rotation.
Returns
Rotation object.

Definition at line 88 of file rotation_lib.cpp.

89{
90 return Rotation(quaternion.normalized());
91}

References Rotation().

Referenced by main().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ fromRotationMatrix()

Rotation MoveG::Rotation::fromRotationMatrix ( const Eigen::Matrix3d &  rotation_matrix)
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);

Parameters
rotation_matrix3x3 rotation matrix.
Returns
Rotation object.

Definition at line 83 of file rotation_lib.cpp.

84{
85 return Rotation(rotation_matrix);
86}

References Rotation().

+ Here is the call graph for this function:

◆ matrixR_dot() [1/2]

Eigen::Matrix3d MoveG::Rotation::matrixR_dot ( const Eigen::Matrix3d &  R,
const Eigen::Matrix3d &  S 
)
static

Calculates the R_dot matrix.

Parameters
RRotation matrix.
SS matrix.
Returns
R_dot matrix

Definition at line 353 of file rotation_lib.cpp.

354{
355 return S * R;
356}

Referenced by main(), and matrixR_dot().

+ Here is the caller graph for this function:

◆ matrixR_dot() [2/2]

Eigen::Matrix3d MoveG::Rotation::matrixR_dot ( const Eigen::Matrix3d &  R,
const Eigen::Vector3d &  omega 
)
static

Calculates the R_dot matrix from an angular velocity vector.

Parameters
RRotation matrix.
omegaAngular velocity vector.
Returns
R_dot matrix

Definition at line 358 of file rotation_lib.cpp.

359{
360 const Eigen::Matrix3d S = matrixS(omega);
361 return matrixR_dot(R, S);
362}
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.

References matrixR_dot(), and matrixS().

+ Here is the call graph for this function:

◆ matrixS()

Eigen::Matrix3d MoveG::Rotation::matrixS ( const Eigen::Vector3d &  omega)
static

Calculates the S matrix.

Parameters
omegaAngular velocity vector. (Different from Euler angle velocities)
Returns
S matrix

Definition at line 345 of file rotation_lib.cpp.

346{
347 Eigen::Matrix3d S = Eigen::Matrix3d::Zero();
348 S << 0, -omega.z(), omega.y(), omega.z(), 0, -omega.x(), -omega.y(), omega.x(), 0;
349 return S;
350}

Referenced by main(), and matrixR_dot().

+ Here is the caller graph for this function:

◆ matrixT()

Eigen::Matrix3d MoveG::Rotation::matrixT ( const Eigen::Vector3d &  angles,
const std::string &  sequence 
)
static

Calculates the T matrix.

Parameters
anglesEuler angles vector.
sequenceSequence of axes (e.g., "ZYX", "ZYZ").
Returns
T matrix
Exceptions
std::runtime_errorIf the matrix is singular (determinant near zero)

Definition at line 364 of file rotation_lib.cpp.

365{
366 checkSequence(sequence);
367
368 Eigen::Matrix3d T = Eigen::Matrix3d::Zero();
369
370 std::array<Eigen::Vector3d, 3> theta;
371
372 for (std::size_t i = 0; i < 3; ++i)
373 {
374 const char c = sequence[i];
375 switch (c)
376 {
377 case 'X':
378 case 'x':
379 theta[i] = Eigen::Vector3d::UnitX();
380 break;
381 case 'Y':
382 case 'y':
383 theta[i] = Eigen::Vector3d::UnitY();
384 break;
385 case 'Z':
386 case 'z':
387 theta[i] = Eigen::Vector3d::UnitZ();
388 break;
389 default:
390 break;
391 }
392 }
393
394 T.col(0) = theta[0];
395
396 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
397
398 for (std::size_t i = 0; i < 2; ++i)
399 {
400 Eigen::Matrix3d Ri;
401
402 const char c = sequence[i];
403 switch (c)
404 {
405 case 'X':
406 case 'x':
407 Ri = Rotation::rotationX(angles[static_cast<Eigen::Index>(i)]);
408 break;
409 case 'Y':
410 case 'y':
411 Ri = Rotation::rotationY(angles[static_cast<Eigen::Index>(i)]);
412 break;
413 case 'Z':
414 case 'z':
415 Ri = Rotation::rotationZ(angles[static_cast<Eigen::Index>(i)]);
416 break;
417 default:
418 Ri = Eigen::Matrix3d::Identity();
419 break;
420 }
421
422 R *= Ri;
423 T.col(static_cast<Eigen::Index>(i + 1)) = R * theta[i + 1];
424 }
425
426 // Check if it is singular and so the determinant is near zero
427 if (std::abs(T.determinant()) < 1e-6)
428 {
429 std::cerr << "WARNING: The matrix is singular\n";
430 throw std::runtime_error("Matrix T is singular, which may cause numerical instability.");
431 }
432
433 return T;
434}
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 rotationX(double angle)
Rotation matrix for a rotation around the X axis.

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:

◆ normalizeAngle()

double MoveG::Rotation::normalizeAngle ( double  angle)
static

Normalizes an angle to the range [-π, π].

Parameters
angleAngle in radians
Returns
Normalized angle in radians within the range [-π, π]

Definition at line 182 of file rotation_lib.cpp.

183{
184 // Use fmod to get the remainder of division by 2π
185 angle = std::fmod(angle, 2 * M_PI);
186
187 // Adjust to the range [-π, π]
188 if (angle > M_PI)
189 {
190 angle -= 2 * M_PI;
191 }
192 else if (angle < -M_PI)
193 {
194 angle += 2 * M_PI;
195 }
196
197 return angle;
198}

Referenced by main(), and normalizeEulerAngles().

+ Here is the caller graph for this function:

◆ normalizeAngleRange()

double MoveG::Rotation::normalizeAngleRange ( double  angle,
double  minVal,
double  maxVal 
)
static

Normalizes an angle to a specified range.

Parameters
angleAngle in radians
minValLower bound of the range
maxValUpper bound of the range
Returns
Normalized angle in radians within the specified range

Definition at line 201 of file rotation_lib.cpp.

202{
203 const double width = maxVal - minVal;
204
205 // Validate range width
206 if (width <= 0)
207 {
208 throw std::invalid_argument("Invalid range: maxVal must be greater than minVal");
209 }
210
211 // Get a value in range [0, width) using modulo
212 const double offsetAngle = std::fmod(angle - minVal, width);
213
214 // Handle negative angles
215 if (offsetAngle < 0)
216 {
217 return offsetAngle + maxVal;
218 }
219 else
220 {
221 return offsetAngle + minVal;
222 }
223}

◆ normalizeEulerAngles()

Eigen::Vector3d MoveG::Rotation::normalizeEulerAngles ( const Eigen::Vector3d &  angles)
static

Normalizes Euler angles to the range [-π, π].

Parameters
anglesVector of Euler angles in radians
Returns
Vector of normalized Euler angles in radians

Definition at line 226 of file rotation_lib.cpp.

227{
228 return Eigen::Vector3d(normalizeAngle(angles.x()),
229 normalizeAngle(angles.y()),
230 normalizeAngle(angles.z()));
231}
static double normalizeAngle(double angle)
Normalizes an angle to the range [-π, π].

References normalizeAngle().

+ Here is the call graph for this function:

◆ operator*()

Rotation MoveG::Rotation::operator* ( const Rotation other) const

Composition of two rotations.

Parameters
otherRotation to compose with.
Returns
New rotation resulting from the composition.

Definition at line 152 of file rotation_lib.cpp.

153{
154 return Rotation(q * other.q);
155}

References q, and Rotation().

+ Here is the call graph for this function:

◆ operator=() [1/2]

Rotation & MoveG::Rotation::operator= ( const Rotation other)

Assignment operator.

Parameters
otherRotation to assign.
Returns
Reference to the current object.

Definition at line 157 of file rotation_lib.cpp.

158{
159 if (this != &other)
160 {
161 q = other.q;
162 }
163 return *this;
164}

References q.

◆ operator=() [2/2]

Rotation & MoveG::Rotation::operator= ( Rotation &&  other)
noexcept

Move assignment operator.

Parameters
otherRotation to assign.
Returns
Reference to the current object.

Definition at line 166 of file rotation_lib.cpp.

167{
168 q = std::move(other.q);
169 return *this;
170}

◆ quaternion_difference()

Eigen::Quaterniond MoveG::Rotation::quaternion_difference ( const Eigen::Quaterniond &  a,
const Eigen::Quaterniond &  b 
)
static

Calculates the difference between two quaternions.

Parameters
aReference quaternion.
bQuaternion to subtract.
Returns
Quaternion resulting from the difference.

Definition at line 294 of file rotation_lib.cpp.

296{
297 return a.inverse() * b;
298}

◆ quaternion_minus()

Eigen::Quaterniond MoveG::Rotation::quaternion_minus ( const Eigen::Quaterniond &  v1,
const Eigen::Quaterniond &  v0 
)
static

Calculates the difference between two quaternions (v1 - v0).

Parameters
v1First quaternion.
v0Second quaternion.
Returns
Quaternion resulting from the subtraction.

Definition at line 310 of file rotation_lib.cpp.

312{
313 return Eigen::Quaterniond(v1.w() - v0.w(), v1.x() - v0.x(), v1.y() - v0.y(), v1.z() - v0.z());
314}

◆ quaternion_negation()

Eigen::Quaterniond MoveG::Rotation::quaternion_negation ( const Eigen::Quaterniond &  v)
static

Negates the quaternion.

Parameters
vQuaternion to negate.
Returns
Negated quaternion.

Definition at line 300 of file rotation_lib.cpp.

301{
302 return Eigen::Quaterniond(-v.w(), -v.x(), -v.y(), -v.z());
303}

◆ quaternion_plus()

Eigen::Quaterniond MoveG::Rotation::quaternion_plus ( const Eigen::Quaterniond &  v1,
const Eigen::Quaterniond &  v0 
)
static

Calculates the sum of two quaternions.

Parameters
v1First quaternion.
v0Second quaternion.
Returns
Quaternion resulting from the addition.

Definition at line 316 of file rotation_lib.cpp.

318{
319 return Eigen::Quaterniond(v1.w() + v0.w(), v1.x() + v0.x(), v1.y() + v0.y(), v1.z() + v0.z());
320}

◆ rad2deg()

double MoveG::Rotation::rad2deg ( double  radian)
static

Converts radians to degrees.

Parameters
radianAngle in radians.
Returns
Angle in degrees.

Definition at line 289 of file rotation_lib.cpp.

290{
291 return radian * 180.0 / M_PI;
292}

Referenced by main(), and printEulerAngles().

+ Here is the caller graph for this function:

◆ rotationX()

Eigen::Matrix3d MoveG::Rotation::rotationX ( double  angle)
static

Rotation matrix for a rotation around the X axis.

Parameters
angleRotation angle in radians.
Returns
3x3 rotation matrix.

Definition at line 323 of file rotation_lib.cpp.

324{
325 Eigen::Matrix3d rot = Eigen::Matrix3d::Identity();
326 rot << 1, 0, 0, 0, cos(angle), -sin(angle), 0, sin(angle), cos(angle);
327 return rot;
328}

Referenced by main(), and matrixT().

+ Here is the caller graph for this function:

◆ rotationY()

Eigen::Matrix3d MoveG::Rotation::rotationY ( double  angle)
static

Rotation matrix for a rotation around the Y axis.

Parameters
angleRotation angle in radians.
Returns
3x3 rotation matrix.

Definition at line 330 of file rotation_lib.cpp.

331{
332 Eigen::Matrix3d rot = Eigen::Matrix3d::Identity();
333 rot << cos(angle), 0, sin(angle), 0, 1, 0, -sin(angle), 0, cos(angle);
334 return rot;
335}

Referenced by main(), and matrixT().

+ Here is the caller graph for this function:

◆ rotationZ()

Eigen::Matrix3d MoveG::Rotation::rotationZ ( double  angle)
static

Rotation matrix for a rotation around the Z axis.

Parameters
angleRotation angle in radians.
Returns
3x3 rotation matrix.

Definition at line 337 of file rotation_lib.cpp.

338{
339 Eigen::Matrix3d rot = Eigen::Matrix3d::Identity();
340 rot << cos(angle), -sin(angle), 0, sin(angle), cos(angle), 0, 0, 0, 1;
341 return rot;
342}

Referenced by main(), and matrixT().

+ Here is the caller graph for this function:

◆ scalar_product()

Eigen::Quaterniond MoveG::Rotation::scalar_product ( const Eigen::Quaterniond &  v,
double  t 
)
static

Calculates the scalar product of a quaternion by a scalar.

Parameters
vQuaternion to scale.
tScale to multiply by.
Returns
Scaled quaternion.

Definition at line 305 of file rotation_lib.cpp.

306{
307 return Eigen::Quaterniond(t * v.w(), t * v.x(), t * v.y(), t * v.z());
308}

◆ toAngleAxis()

Eigen::AngleAxisd MoveG::Rotation::toAngleAxis ( ) const

Converts the rotation to an axis-angle representation.

Returns
Axis-angle representation of the rotation.

Definition at line 121 of file rotation_lib.cpp.

122{
123 return Eigen::AngleAxisd(q);
124}

References q.

Referenced by main().

+ Here is the caller graph for this function:

◆ toEulerAngles()

Eigen::Vector3d MoveG::Rotation::toEulerAngles ( bool  intrinsic = true,
const std::string &  sequence = "ZYX" 
) const

Converts the rotation to Euler angles.

Parameters
intrinsicIf true, uses intrinsic rotations; otherwise, extrinsic.
sequenceSequence of axes (e.g., "ZYX").
Returns
Vector containing the three Euler angles.

Definition at line 127 of file rotation_lib.cpp.

128{
129 checkSequence(sequence);
130
131 const int a0 = axisToIndex(sequence[0]);
132 const int a1 = axisToIndex(sequence[1]);
133 const int a2 = axisToIndex(sequence[2]);
134
135 Eigen::Vector3d angles = Eigen::Vector3d::Zero();
136
137 if (intrinsic)
138 {
139 // For intrinsic rotations, reverse the order of axes
140 angles = q.toRotationMatrix().eulerAngles(a2, a1, a0).reverse();
141 }
142 else
143 {
144 // For extrinsic rotations, use the axes as they are
145 angles = q.toRotationMatrix().eulerAngles(a0, a1, a2);
146 }
147
148 return angles;
149}
static int axisToIndex(char axis)
Converts an axis character to index.

References axisToIndex(), checkSequence(), and q.

Referenced by main().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ toQuaternion()

Eigen::Quaterniond MoveG::Rotation::toQuaternion ( ) const

Converts the rotation to a quaternion.

Returns
Quaternion representing the rotation.

Definition at line 115 of file rotation_lib.cpp.

116{
117 return q;
118}

References q.

Referenced by main().

+ Here is the caller graph for this function:

◆ toRotationMatrix()

Eigen::Matrix3d MoveG::Rotation::toRotationMatrix ( ) const

Converts the rotation to a rotation matrix.

Returns
3x3 rotation matrix.

Definition at line 109 of file rotation_lib.cpp.

110{
111 return q.toRotationMatrix();
112}

References q.

Referenced by main().

+ Here is the caller graph for this function:

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const Rotation rotation 
)
friend

Outputs the rotation to a stream in quaternion format.

Parameters
osStream to output to.
rotationRotation to output.
Returns
Reference to the output stream.

Definition at line 173 of file rotation_lib.cpp.

174{
175 Eigen::Quaterniond quat = rotation.toQuaternion();
176 os << "Rotation (quaternion x,y,z,w): [" << quat.x() << ", " << quat.y() << ", " << quat.z()
177 << ", " << quat.w() << "]";
178 return os;
179}

Member Data Documentation

◆ q

Eigen::Quaterniond MoveG::Rotation::q
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().


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