15 #ifndef GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_
16 #define GEOMETRY__VECTOR3__GET_NORMAL_VECTOR_HPP_
20 #include <geometry_msgs/msg/vector3.hpp>
27 typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> =
nullptr>
32 return geometry_msgs::build<geometry_msgs::msg::Vector3>()
33 .x(rotation_matrix(0, 2))
34 .y(rotation_matrix(1, 2))
35 .z(rotation_matrix(2, 2));
auto getRotationMatrix(T quat) -> Eigen::Matrix3d
Definition: get_rotation_matrix.hpp:33
auto getNormalVector(const T &orientation) -> geometry_msgs::msg::Vector3
Definition: get_normal_vector.hpp:28
Definition: bounding_box.hpp:32