scenario_simulator_v2 C++ API
continuous_transform_broadcaster.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 CONCEALER__CONTINUOUS_TRANSFORM_BROADCASTER_HPP_
16 #define CONCEALER__CONTINUOUS_TRANSFORM_BROADCASTER_HPP_
17 
18 #include <tf2_ros/buffer.h>
19 #include <tf2_ros/transform_broadcaster.h>
20 #include <tf2_ros/transform_listener.h>
21 
22 #include <chrono>
23 #include <geometry_msgs/msg/pose.hpp>
24 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
25 
26 namespace concealer
27 {
28 template <typename Node>
30 {
31  tf2_ros::Buffer transform_buffer;
32 
33  tf2_ros::TransformBroadcaster transform_broadcaster;
34 
35  geometry_msgs::msg::TransformStamped current_transform;
36 
37  const rclcpp::TimerBase::SharedPtr timer;
38 
39  void updateTransform()
40  {
41  if (
42  not current_transform.header.frame_id.empty() and
43  not current_transform.child_frame_id.empty()) //
44  {
45  current_transform.header.stamp = static_cast<Node &>(*this).get_clock()->now();
46  return transform_broadcaster.sendTransform(current_transform);
47  }
48  }
49 
50 public:
51  const auto & setTransform(const geometry_msgs::msg::Pose & pose)
52  {
53  current_transform.header.stamp = static_cast<Node &>(*this).get_clock()->now();
54  current_transform.header.frame_id = "map";
55  current_transform.child_frame_id = "base_link";
56  current_transform.transform.translation.x = pose.position.x;
57  current_transform.transform.translation.y = pose.position.y;
58  current_transform.transform.translation.z = pose.position.z;
59  current_transform.transform.rotation = pose.orientation;
60 
61  return current_transform;
62  }
63 
65  : transform_buffer(static_cast<Node &>(*this).get_clock()),
66  transform_broadcaster(static_cast<Node *>(this)),
67  timer(static_cast<Node &>(*this).create_wall_timer(
68  std::chrono::milliseconds(5), [this]() { return updateTransform(); }))
69  {
70  }
71 };
72 } // namespace concealer
73 
74 #endif // CONCEALER__CONTINUOUS_TRANSFORM_BROADCASTER_HPP_
Definition: continuous_transform_broadcaster.hpp:30
ContinuousTransformBroadcaster()
Definition: continuous_transform_broadcaster.hpp:64
const auto & setTransform(const geometry_msgs::msg::Pose &pose)
Definition: continuous_transform_broadcaster.hpp:51
Definition: autoware_universe.hpp:40
Definition: cache.hpp:27