scenario_simulator_v2 C++ API
get_angle_difference.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_
16 #define GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_
17 
18 #include <Eigen/Geometry>
20 
21 namespace math
22 {
23 namespace geometry
24 {
25 template <
26  typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> = nullptr>
27 auto getAngleDifference(const T & quat1, const T & quat2) -> double
28 {
29  const Eigen::Quaterniond q1(quat1.w, quat1.x, quat1.y, quat1.z);
30  const Eigen::Quaterniond q2(quat2.w, quat2.x, quat2.y, quat2.z);
31 
32  const Eigen::AngleAxisd delta(q1.inverse() * q2);
33 
34  return std::abs(delta.angle()); // [rad]
35 }
36 } // namespace geometry
37 } // namespace math
38 
39 #endif // GEOMETRY__QUATERNION__GET_ANGLE_DIFFERENCE_HPP_
auto getAngleDifference(const T &quat1, const T &quat2) -> double
Definition: get_angle_difference.hpp:27
Definition: bounding_box.hpp:32