15 #ifndef GEOMETRY__QUATERNION__QUATERNION_TO_EULER_HPP_
16 #define GEOMETRY__QUATERNION__QUATERNION_TO_EULER_HPP_
18 #include <tf2/LinearMath/Matrix3x3.h>
22 #include <geometry_msgs/msg/vector3.hpp>
29 typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> =
nullptr>
32 tf2::Quaternion tf_quat(q.x, q.y, q.z, q.w);
33 tf2::Matrix3x3 mat(tf_quat);
37 mat.getRPY(roll, pitch, yaw);
38 return geometry_msgs::build<geometry_msgs::msg::Vector3>().x(roll).y(pitch).z(yaw);
auto convertQuaternionToEulerAngle(const T &q)
Definition: quaternion_to_euler.hpp:30
Definition: bounding_box.hpp:32