15 #ifndef GEOMETRY__QUATERNION__SLERP_HPP_
16 #define GEOMETRY__QUATERNION__SLERP_HPP_
20 #include <geometry_msgs/msg/quaternion.hpp>
26 typename T,
typename U,
typename V,
28 std::conjunction_v<IsLikeQuaternion<T>, IsLikeQuaternion<U>, std::is_scalar<V>>,
29 std::nullptr_t> =
nullptr>
30 auto slerp(T quat1, U quat2, V t)
32 double qr = quat1.w * quat2.w + quat1.x * quat2.x + quat1.y * quat2.y + quat1.z * quat2.z;
33 double ss = 1.0 - qr * qr;
34 constexpr
double e = std::numeric_limits<double>::epsilon();
35 if (std::fabs(ss) <= e) {
36 return geometry_msgs::build<geometry_msgs::msg::Quaternion>()
42 double sp = std::sqrt(ss);
43 double ph = std::acos(qr);
45 double t1 = std::sin(pt) / sp;
46 double t0 = std::sin(ph - pt) / sp;
48 return geometry_msgs::build<geometry_msgs::msg::Quaternion>()
49 .x(quat1.x * t0 + quat2.x * t1)
50 .y(quat1.y * t0 + quat2.y * t1)
51 .z(quat1.z * t0 + quat2.z * t1)
52 .w(quat1.w * t0 + quat2.w * t1);
auto slerp(T quat1, U quat2, V t)
Definition: slerp.hpp:30
Definition: bounding_box.hpp:32