scenario_simulator_v2 C++ API
quaternion_to_euler.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__QUATERNION_TO_EULER_HPP_
16 #define GEOMETRY__QUATERNION__QUATERNION_TO_EULER_HPP_
17 
18 #include <tf2/LinearMath/Matrix3x3.h>
19 
20 #include <cmath>
22 #include <geometry_msgs/msg/vector3.hpp>
23 
24 namespace math
25 {
26 namespace geometry
27 {
28 template <
29  typename T, std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>>, std::nullptr_t> = nullptr>
31 {
32  tf2::Quaternion tf_quat(q.x, q.y, q.z, q.w);
33  tf2::Matrix3x3 mat(tf_quat);
34  double roll;
35  double pitch;
36  double yaw;
37  mat.getRPY(roll, pitch, yaw);
38  return geometry_msgs::build<geometry_msgs::msg::Vector3>().x(roll).y(pitch).z(yaw);
39 }
40 } // namespace geometry
41 } // namespace math
42 
43 #endif // GEOMETRY__QUATERNION__QUATERNION_TO_EULER_HPP_
auto convertQuaternionToEulerAngle(const T &q)
Definition: quaternion_to_euler.hpp:30
Definition: bounding_box.hpp:32