15 #ifndef GEOMETRY__QUATERNION__DIRECTION_TO_QUATERNION_HPP_
16 #define GEOMETRY__QUATERNION__DIRECTION_TO_QUATERNION_HPP_
21 #include <geometry_msgs/msg/quaternion.hpp>
22 #include <geometry_msgs/msg/vector3.hpp>
30 const auto euler_angles = geometry_msgs::build<geometry_msgs::msg::Vector3>()
33 .z(std::atan2(dy, dx));
38 typename T, std::enable_if_t<std::conjunction_v<IsLikeVector3<T>>, std::nullptr_t> =
nullptr>
auto hypot(const T &from, const U &to)
Definition: hypot.hpp:28
auto convertDirectionToQuaternion(const double dx, const double dy, const double dz)
Definition: direction_to_quaternion.hpp:28
auto convertEulerAngleToQuaternion(const T &v)
Definition: euler_to_quaternion.hpp:30
Definition: bounding_box.hpp:32