PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
geometry.hpp
1 /****************************************************************************
2  * Copyright (c) 2024 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
25 #pragma once
26 
27 #include <Eigen/Eigen>
28 
29 namespace px4_ros2
30 {
38 template<typename Type>
39 Type radToDeg(Type rad)
40 {
41  return rad * static_cast<Type>(180.0 / M_PI);
42 }
43 
47 template<typename Type>
48 Type degToRad(Type deg)
49 {
50  return deg * static_cast<Type>(M_PI / 180.0);
51 }
52 
53 namespace literals
54 {
55 static inline constexpr float operator"" _deg(long double degrees)
56 {
57  return static_cast<float>(degrees * M_PI / 180.0);
58 }
59 static inline constexpr float operator"" _rad(long double radians)
60 {
61  return static_cast<float>(radians);
62 }
63 }
64 
71 template<typename Type>
72 Type wrapPi(Type angle)
73 {
74  while (angle >= M_PI) {
75  angle -= 2.0 * M_PI;
76  }
77  while (angle < -M_PI) {
78  angle += 2.0 * M_PI;
79  }
80  return angle;
81 }
82 
90 template<typename Type>
91 Eigen::Matrix<Type, 3, 1> quaternionToEulerRpy(const Eigen::Quaternion<Type> & q)
92 {
93  Eigen::Matrix<Type, 3, 1> angles;
94  const Eigen::Matrix<Type, 3, 3> dcm = q.toRotationMatrix();
95 
96  angles.y() = asin(-dcm.coeff(2, 0));
97 
98  if ((std::fabs(angles.y() - static_cast<Type>(M_PI / 2))) < static_cast<Type>(1.0e-3)) {
99  angles.x() = 0;
100  angles.z() = atan2(dcm.coeff(1, 2), dcm.coeff(0, 2));
101  } else if ((std::fabs(angles.y() + static_cast<Type>(M_PI / 2))) < static_cast<Type>(1.0e-3)) {
102  angles.x() = 0;
103  angles.z() = atan2(-dcm.coeff(1, 2), -dcm.coeff(0, 2));
104  } else {
105  angles.x() = atan2(dcm.coeff(2, 1), dcm.coeff(2, 2));
106  angles.z() = atan2(dcm.coeff(1, 0), dcm.coeff(0, 0));
107  }
108 
109  return angles;
110 }
111 
118 template<typename Type>
119 Eigen::Quaternion<Type> eulerRpyToQuaternion(const Eigen::Matrix<Type, 3, 1> & euler)
120 {
121  return Eigen::Quaternion<Type>(
122  Eigen::AngleAxis<Type>(euler[2], Eigen::Matrix<Type, 3, 1>::UnitZ()) *
123  Eigen::AngleAxis<Type>(euler[1], Eigen::Matrix<Type, 3, 1>::UnitY()) *
124  Eigen::AngleAxis<Type>(euler[0], Eigen::Matrix<Type, 3, 1>::UnitX()));
125 }
126 
135 template<typename Type>
136 Eigen::Quaternion<Type> eulerRpyToQuaternion(const Type roll, const Type pitch, const Type yaw)
137 {
138  return eulerRpyToQuaternion(Eigen::Matrix<Type, 3, 1>{roll, pitch, yaw});
139 }
140 
147 template<typename Type>
148 Type quaternionToRoll(const Eigen::Quaternion<Type> & q)
149 {
150  return quaternionToEulerRpy(q)[0];
151 }
152 
159 template<typename Type>
160 Type quaternionToPitch(const Eigen::Quaternion<Type> & q)
161 {
162  return quaternionToEulerRpy(q)[1];
163 }
164 
171 template<typename Type>
172 Type quaternionToYaw(const Eigen::Quaternion<Type> & q)
173 {
174  return quaternionToEulerRpy(q)[2];
175 }
176 
178 } // namespace px4_ros2
Eigen::Matrix< Type, 3, 1 > quaternionToEulerRpy(const Eigen::Quaternion< Type > &q)
Converts a quaternion to RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) XYZ axes correspond to...
Definition: geometry.hpp:91
Eigen::Quaternion< Type > eulerRpyToQuaternion(const Type roll, const Type pitch, const Type yaw)
Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion.
Definition: geometry.hpp:136
Type quaternionToRoll(const Eigen::Quaternion< Type > &q)
Convert quaternion to roll angle in extrinsic RPY order (intrinsic YPR)
Definition: geometry.hpp:148
Type degToRad(Type deg)
Converts degrees to radians.
Definition: geometry.hpp:48
Type wrapPi(Type angle)
Wraps an angle to the range [-pi, pi).
Definition: geometry.hpp:72
Type quaternionToPitch(const Eigen::Quaternion< Type > &q)
Convert quaternion to pitch angle in extrinsic RPY order (intrinsic YPR)
Definition: geometry.hpp:160
Type radToDeg(Type rad)
Converts radians to degrees.
Definition: geometry.hpp:39
Type quaternionToYaw(const Eigen::Quaternion< Type > &q)
Convert quaternion to yaw angle in extrinsic RPY order (intrinsic YPR)
Definition: geometry.hpp:172