tf2_utils.hpp
Go to the documentation of this file.
1 #pragma once
2 
11 #include <geometry_msgs/Quaternion.h>
13 
14 namespace cras
15 {
16 
24 void getRPY(const ::tf2::Quaternion& quat, double& roll, double& pitch, double& yaw);
25 
33 void getRPY(const ::geometry_msgs::Quaternion& quat, double& roll, double& pitch, double& yaw);
34 
40 double getRoll(const ::tf2::Quaternion& quat);
41 
47 double getRoll(const ::geometry_msgs::Quaternion& quat);
48 
54 double getPitch(const ::tf2::Quaternion& quat);
55 
61 double getPitch(const ::geometry_msgs::Quaternion& quat);
62 
68 double getYaw(const ::tf2::Quaternion& quat);
69 
75 double getYaw(const ::geometry_msgs::Quaternion& quat);
76 
77 }
cras
Definition: any.hpp:15
Quaternion.h
cras::getYaw
double getYaw(const ::tf2::Quaternion &quat)
Get yaw from the given quaternion.
cras::getRoll
double getRoll(const ::tf2::Quaternion &quat)
Get roll from the given quaternion.
cras::getRPY
void getRPY(const ::tf2::Quaternion &quat, double &roll, double &pitch, double &yaw)
Get roll, pitch and yaw from the given quaternion.
cras::getPitch
double getPitch(const ::tf2::Quaternion &quat)
Get pitch from the given quaternion.


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:04