Autoware.Auto
tf2_autoware_auto_msgs.hpp
Go to the documentation of this file.
1 // Copyright 2020, The Autoware Foundation.
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.
16 
17 #ifndef AUTOWARE_AUTO_TF2__TF2_AUTOWARE_AUTO_MSGS_HPP_
18 #define AUTOWARE_AUTO_TF2__TF2_AUTOWARE_AUTO_MSGS_HPP_
19 
20 #include <tf2/convert.h>
21 #include <tf2/time.h>
22 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
23 #include <autoware_auto_msgs/msg/bounding_box_array.hpp>
24 #include <autoware_auto_msgs/msg/bounding_box.hpp>
25 #include <geometry_msgs/msg/transform_stamped.hpp>
26 #include <autoware_auto_msgs/msg/quaternion32.hpp>
27 #include <geometry_msgs/msg/point32.hpp>
28 #include <kdl/frames.hpp>
29 #include <common/types.hpp>
30 #include <string>
31 
32 
37 
38 namespace tf2
39 {
40 
41 
42 /*************/
44 /*************/
45 
52 template<>
53 inline
55  const geometry_msgs::msg::Point32 & t_in, geometry_msgs::msg::Point32 & t_out,
56  const geometry_msgs::msg::TransformStamped & transform)
57 {
58  KDL::Vector v_out = gmTransformToKDL(transform) * KDL::Vector(t_in.x, t_in.y, t_in.z);
59  t_out.x = static_cast<float>(v_out[0]);
60  t_out.y = static_cast<float>(v_out[1]);
61  t_out.z = static_cast<float>(v_out[2]);
62 }
63 
64 /******************/
66 /******************/
67 
74 template<>
75 inline
77  const autoware_auto_msgs::msg::Quaternion32 & t_in,
78  autoware_auto_msgs::msg::Quaternion32 & t_out,
79  const geometry_msgs::msg::TransformStamped & transform)
80 {
81  KDL::Rotation r_in = KDL::Rotation::Quaternion(t_in.x, t_in.y, t_in.z, t_in.w);
82  KDL::Rotation out = gmTransformToKDL(transform).M * r_in;
83 
84  double qx, qy, qz, qw;
85  out.GetQuaternion(qx, qy, qz, qw);
86  t_out.x = static_cast<float32_t>(qx);
87  t_out.y = static_cast<float32_t>(qy);
88  t_out.z = static_cast<float32_t>(qz);
89  t_out.w = static_cast<float32_t>(qw);
90 }
91 
92 
93 /******************/
95 /******************/
96 
103 template<>
104 inline
106  const BoundingBox & t_in, BoundingBox & t_out,
107  const geometry_msgs::msg::TransformStamped & transform)
108 {
109  t_out = t_in;
110  doTransform(t_in.orientation, t_out.orientation, transform);
111  doTransform(t_in.centroid, t_out.centroid, transform);
112  doTransform(t_in.corners[0], t_out.corners[0], transform);
113  doTransform(t_in.corners[1], t_out.corners[1], transform);
114  doTransform(t_in.corners[2], t_out.corners[2], transform);
115  doTransform(t_in.corners[3], t_out.corners[3], transform);
116  // TODO(jitrc): add conversion for other fields of BoundingBox, such as heading, variance, size
117 }
118 
119 
120 /**********************/
122 /**********************/
123 
129 template<>
130 inline
131 tf2::TimePoint getTimestamp(const BoundingBoxArray & t)
132 {
133  return tf2_ros::fromMsg(t.header.stamp);
134 }
135 
141 template<>
142 inline
143 std::string getFrameId(const BoundingBoxArray & t) {return t.header.frame_id;}
144 
151 template<>
152 inline
154  const BoundingBoxArray & t_in,
155  BoundingBoxArray & t_out,
156  const geometry_msgs::msg::TransformStamped & transform)
157 {
158  t_out = t_in;
159  for (auto idx = 0U; idx < t_in.boxes.size(); idx++) {
160  doTransform(t_out.boxes[idx], t_out.boxes[idx], transform);
161  }
162  t_out.header.stamp = transform.header.stamp;
163  t_out.header.frame_id = transform.header.frame_id;
164 }
165 
166 } // namespace tf2
167 
168 #endif // AUTOWARE_AUTO_TF2__TF2_AUTOWARE_AUTO_MSGS_HPP_
tf2::getFrameId
std::string getFrameId(const BoundingBoxArray &t)
Extract a frame ID from the header of a BoundingBoxArray message. This function is a specialization o...
Definition: tf2_autoware_auto_msgs.hpp:143
types.hpp
This file includes common type definition.
catr_diff.t
t
Definition: catr_diff.py:22
tf2::getTimestamp
tf2::TimePoint getTimestamp(const BoundingBoxArray &t)
Extract a timestamp from the header of a BoundingBoxArray message. This function is a specialization ...
Definition: tf2_autoware_auto_msgs.hpp:131
BoundingBoxArray
autoware_auto_msgs::msg::BoundingBoxArray BoundingBoxArray
Definition: tf2_autoware_auto_msgs.hpp:35
motion::motion_testing_nodes::TransformStamped
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
BoundingBox
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: tf2_autoware_auto_msgs.hpp:36
tf2
Definition: tf2_autoware_auto_msgs.hpp:38
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:37
tf2::doTransform
void doTransform(const geometry_msgs::msg::Point32 &t_in, geometry_msgs::msg::Point32 &t_out, const geometry_msgs::msg::TransformStamped &transform)
Apply a geometry_msgs TransformStamped to an geometry_msgs Point32 type. This function is a specializ...
Definition: tf2_autoware_auto_msgs.hpp:54