15 #ifndef GEOMETRY__QUATERNION__EULER_TO_QUATERNION_HPP_
16 #define GEOMETRY__QUATERNION__EULER_TO_QUATERNION_HPP_
18 #include <tf2/LinearMath/Matrix3x3.h>
22 #include <geometry_msgs/msg/quaternion.hpp>
29 typename T, std::enable_if_t<std::conjunction_v<IsLikeVector3<T>>, std::nullptr_t> =
nullptr>
32 const double & roll = v.x;
33 const double & pitch = v.y;
34 const double & yaw = v.z;
35 tf2::Quaternion tf_quat;
36 tf_quat.setRPY(roll, pitch, yaw);
37 return geometry_msgs::build<geometry_msgs::msg::Quaternion>()
auto convertEulerAngleToQuaternion(const T &v)
Definition: euler_to_quaternion.hpp:30
Definition: bounding_box.hpp:32