15 #ifndef CONCEALER__CONTINUOUS_TRANSFORM_BROADCASTER_HPP_ 
   16 #define CONCEALER__CONTINUOUS_TRANSFORM_BROADCASTER_HPP_ 
   18 #include <tf2_ros/buffer.h> 
   19 #include <tf2_ros/transform_broadcaster.h> 
   20 #include <tf2_ros/transform_listener.h> 
   23 #include <geometry_msgs/msg/pose.hpp> 
   24 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp> 
   28 template <
typename Node>
 
   31   tf2_ros::Buffer transform_buffer;
 
   33   tf2_ros::TransformBroadcaster transform_broadcaster;
 
   35   geometry_msgs::msg::TransformStamped current_transform;
 
   37   const rclcpp::TimerBase::SharedPtr timer;
 
   39   void updateTransform()
 
   42       not current_transform.header.frame_id.empty() and
 
   43       not current_transform.child_frame_id.empty())  
 
   45       current_transform.header.stamp = 
static_cast<Node &
>(*this).get_clock()->now();
 
   46       return transform_broadcaster.sendTransform(current_transform);
 
   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;
 
   61     return current_transform;
 
   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(); }))
 
Definition: autoware_universe.hpp:40
Definition: lanelet_wrapper.hpp:40
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66