15 #ifndef GEOMETRY__QUATERNION__GET_ROTATION_MATRIX_HPP_
16 #define GEOMETRY__QUATERNION__GET_ROTATION_MATRIX_HPP_
18 #include <tf2/LinearMath/Matrix3x3.h>
23 #define EIGEN_MPL2_ONLY
25 #include <Eigen/Geometry>
32 typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> =
nullptr>
39 Eigen::Matrix3d ret(3, 3);
41 ret << x * x - y * y - z * z + w * w, 2 * (x * y - z * w), 2 * (z * x + w * y),
42 2 * (x * y + z * w), -x * x + y * y - z * z + w * w, 2 * (y * z - x * w),
43 2 * (z * x - w * y), 2 * (y * z + w * x), -x * x - y * y + z * z + w * w;
auto getRotationMatrix(T quat) -> Eigen::Matrix3d
Definition: get_rotation_matrix.hpp:33
Definition: bounding_box.hpp:32