19 #ifndef TRANSFORM_HELPERS_HPP
20 #define TRANSFORM_HELPERS_HPP
22 #include <geometry_msgs/Transform.h>
23 #include <geometry_msgs/Pose.h>
24 #include <tf2/LinearMath/Matrix3x3.h>
33 inline double getYaw(
const geometry_msgs::Pose& pose)
35 double yaw, _pitch, _roll;
36 tf2::Matrix3x3(tf2::Quaternion(pose.orientation.x, pose.orientation.y,
37 pose.orientation.z, pose.orientation.w)).getEulerYPR(yaw, _pitch, _roll);
41 inline double getYaw(
const geometry_msgs::Transform& pose)
43 double yaw, _pitch, _roll;
44 tf2::Matrix3x3(tf2::Quaternion(pose.rotation.x, pose.rotation.y, pose.rotation.z, pose.rotation.w)).getEulerYPR(yaw, _pitch, _roll);