tf2  master
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
utils.h
Go to the documentation of this file.
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
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 TF2__IMPL__UTILS_H_
16 #define TF2__IMPL__UTILS_H_
17 
18 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
21 
22 namespace tf2
23 {
24 namespace impl
25 {
26 
31 inline
33 {
34  return q;
35 }
36 
41 inline
42 tf2::Quaternion toQuaternion(const geometry_msgs::msg::Quaternion & q)
43 {
44  tf2::Quaternion res;
45  fromMsg(q, res);
46  return res;
47 }
48 
53 inline
54 tf2::Quaternion toQuaternion(const geometry_msgs::msg::QuaternionStamped & q)
55 {
56  tf2::Quaternion res;
57  fromMsg(q.quaternion, res);
58  return res;
59 }
60 
65 template<typename T>
67 {
68  geometry_msgs::msg::QuaternionStamped q = toMsg<tf2::Stamped<T>,
69  geometry_msgs::msg::QuaternionStamped>(t);
70  return toQuaternion(q);
71 }
72 
78 template<typename T>
80 {
81  geometry_msgs::msg::Quaternion q = toMsg<T, geometry_msgs::msg::QuaternionStamped>(t);
82  return toQuaternion(q);
83 }
84 
94 inline
95 void getEulerYPR(const tf2::Quaternion & q, double & yaw, double & pitch, double & roll)
96 {
97  const double pi_2 = 1.57079632679489661923;
98  double sqw;
99  double sqx;
100  double sqy;
101  double sqz;
102 
103  sqx = q.x() * q.x();
104  sqy = q.y() * q.y();
105  sqz = q.z() * q.z();
106  sqw = q.w() * q.w();
107 
108  // Cases derived from https://orbitalstation.wordpress.com/tag/quaternion/
109  // normalization added from urdfom_headers
110  double sarg = -2 * (q.x() * q.z() - q.w() * q.y()) / (sqx + sqy + sqz + sqw);
111  if (sarg <= -0.99999) {
112  pitch = -0.5 * pi_2;
113  roll = 0;
114  yaw = -2 * atan2(q.y(), q.x());
115  } else if (sarg >= 0.99999) {
116  pitch = 0.5 * pi_2;
117  roll = 0;
118  yaw = 2 * atan2(q.y(), q.x());
119  } else {
120  pitch = asin(sarg);
121  roll = atan2(2 * (q.y() * q.z() + q.w() * q.x()), sqw - sqx - sqy + sqz);
122  yaw = atan2(2 * (q.x() * q.y() + q.w() * q.z()), sqw + sqx - sqy - sqz);
123  }
124 }
125 
132 inline
133 double getYaw(const tf2::Quaternion & q)
134 {
135  double yaw;
136 
137  double sqw;
138  double sqx;
139  double sqy;
140  double sqz;
141 
142  sqx = q.x() * q.x();
143  sqy = q.y() * q.y();
144  sqz = q.z() * q.z();
145  sqw = q.w() * q.w();
146 
147  // Cases derived from https://orbitalstation.wordpress.com/tag/quaternion/
148  // normalization added from urdfom_headers
149  double sarg = -2 * (q.x() * q.z() - q.w() * q.y()) / (sqx + sqy + sqz + sqw);
150 
151  if (sarg <= -0.99999) {
152  yaw = -2 * atan2(q.y(), q.x());
153  } else if (sarg >= 0.99999) {
154  yaw = 2 * atan2(q.y(), q.x());
155  } else {
156  yaw = atan2(2 * (q.x() * q.y() + q.w() * q.z()), sqw + sqx - sqy - sqz);
157  }
158  return yaw;
159 }
160 
161 } // namespace impl
162 } // namespace tf2
163 #endif // TF2__IMPL__UTILS_H_
tf2::fromMsg
void fromMsg(const A &, B &b)
Function that converts from a ROS message type to another type. It has to be implemented by each data...
tf2::Stamped
The data type which will be cross compatable with geometry_msgs This is the tf2 datatype equivilant o...
Definition: transform_datatypes.h:46
tf2::impl::toQuaternion
tf2::Quaternion toQuaternion(const tf2::Quaternion &q)
Definition: utils.h:32
Quaternion.h
tf2::impl::getEulerYPR
void getEulerYPR(const tf2::Quaternion &q, double &yaw, double &pitch, double &roll)
Definition: utils.h:95
tf2::impl::getYaw
double getYaw(const tf2::Quaternion &q)
Definition: utils.h:133
tf2
Definition: buffer_core.h:53
tf2::Quaternion
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:29
transform_datatypes.h