20#include <carma_ros2_utils/carma_lifecycle_node.hpp>
21#include <tf2/exceptions.h>
22#include <tf2_ros/transform_listener.h>
23#include <tf2_ros/buffer.h>
24#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
25#include <tf2_sensor_msgs/tf2_sensor_msgs.hpp>
26#include <autoware_auto_tf2/tf2_autoware_auto_msgs_extension.hpp>
28#include <gtest/gtest_prod.h>
32 namespace std_ph = std::placeholders;
33 using std_ms = std::chrono::milliseconds;
61 Transformer(
Config config, std::shared_ptr<tf2_ros::Buffer> buffer, std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> node)
84 bool transform(
const T &in, T &out,
const std::string &target_frame,
const std_ms timeout)
89 buffer_->transform(in, out, target_frame, timeout);
91 catch (tf2::TransformException &ex)
93 std::string error = ex.what();
94 error =
"Failed to get transform with exception: " + error;
95 auto& clk = *
node_->get_clock();
96 RCLCPP_WARN_THROTTLE(
node_->get_logger(), clk, 1000, error.c_str());
132 sensor_msgs::msg::PointCloud2 out_msg;
133 out_msg.data.reserve(in_msg->data.size());
136 if (!transform(*in_msg, out_msg, config_.target_frame,
std_ms(config_.timeout)))
145 if (out_msg.height == 1)
147 out_msg.row_step = out_msg.data.size();
150 output_pub_->publish(out_msg);