Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
frame_transformer_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2021 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
17#include <boost/algorithm/string/trim.hpp>
18
19namespace frame_transformer
20{
21 namespace std_ph = std::placeholders;
22
23 Node::Node(const rclcpp::NodeOptions &options)
24 : carma_ros2_utils::CarmaLifecycleNode(options)
25 {
26 // Create default config
27 config_ = Config();
28
29 // Declare parameters and defaults
30 config_.message_type = declare_parameter<std::string>("message_type", config_.message_type);
31 config_.target_frame = declare_parameter<std::string>("target_frame", config_.target_frame);
32 config_.queue_size = declare_parameter<int>("queue_size", config_.queue_size);
33 config_.timeout = declare_parameter<int>("timeout", config_.timeout);
34 }
35
36 std::unique_ptr<TransformerBase> Node::build_transformer() {
37
38 // NOTE: IMU messages could be added once imu_pipeline package is ported to noetic and added as a dependency
39
40 auto type = config_.message_type;
41 boost::algorithm::trim(type); // Trim white space from the type string
42
43 if (type == "geometry_msgs/Vector3Stamped")
44 return std::make_unique<Transformer<geometry_msgs::msg::Vector3Stamped>>(config_, buffer_, shared_from_this());
45
46 else if (type == "geometry_msgs/PointStamped")
47 return std::make_unique<Transformer<geometry_msgs::msg::PointStamped>>(config_, buffer_, shared_from_this());
48
49 else if (type == "geometry_msgs/PoseStamped")
50 return std::make_unique<Transformer<geometry_msgs::msg::PoseStamped>>(config_, buffer_, shared_from_this());
51
52 else if (type == "geometry_msgs/PoseWithCovarianceStamped")
53 return std::make_unique<Transformer<geometry_msgs::msg::PoseWithCovarianceStamped>>(config_, buffer_, shared_from_this());
54
55 else if (type == "geometry_msgs/QuaternionStamped")
56 return std::make_unique<Transformer<geometry_msgs::msg::QuaternionStamped>>(config_, buffer_, shared_from_this());
57
58 else if (type == "geometry_msgs/TransformStamped")
59 return std::make_unique<Transformer<geometry_msgs::msg::TransformStamped>>(config_, buffer_, shared_from_this());
60
61 else if (type == "sensor_msgs/PointCloud2")
62 return std::make_unique<Transformer<sensor_msgs::msg::PointCloud2>>(config_, buffer_, shared_from_this());
63
64 else if (type == "autoware_auto_msgs/BoundingBoxArray")
65 return std::make_unique<Transformer<autoware_auto_msgs::msg::BoundingBoxArray>>(config_, buffer_, shared_from_this());
66
67 else if (type == "autoware_auto_msgs/DetectedObjects")
68 return std::make_unique<Transformer<autoware_auto_msgs::msg::DetectedObjects>>(config_, buffer_, shared_from_this());
69
70 else
71 return nullptr;
72
73 }
74
75 carma_ros2_utils::CallbackReturn Node::handle_on_configure(const rclcpp_lifecycle::State &)
76 {
77 // Reset config
78 config_ = Config();
79
80 // Load parameters
81 get_parameter<std::string>("message_type", config_.message_type);
82 get_parameter<std::string>("target_frame", config_.target_frame);
83 get_parameter<int>("queue_size", config_.queue_size);
84 get_parameter<int>("timeout", config_.timeout);
85
86
87 RCLCPP_INFO_STREAM(get_logger(), "Loaded params: " << config_);
88
89 // NOTE: Due to the nature of this node generating sub/pubs based of parameters.
90 // Dynamically changing the parameters is not recommended. Therefore a parameter callback is not implemented.
91
92
93 buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
94
95 if (config_.timeout != 0) {
96 buffer_->setUsingDedicatedThread(true);
97 }
98
99 listener_ = std::make_shared<tf2_ros::TransformListener>(*buffer_, true);
100
101 // Set the transformer based on the specified message type
103
104 if (!transformer_) {
105 RCLCPP_ERROR_STREAM(get_logger(), "Failed to build transformer for specified message_type: " << config_.message_type);
106 return CallbackReturn::FAILURE;
107 }
108
109 // Return success if everthing initialized successfully
110 return CallbackReturn::SUCCESS;
111 }
112
113 carma_ros2_utils::CallbackReturn Node::handle_on_cleanup(const rclcpp_lifecycle::State &) {
114
115 transformer_.reset(nullptr); // On cleanup clear the old transformer
116 buffer_.reset(); // On cleanup clear the old buffer
117 listener_.reset(); // On cleanup clear the old listener
118
119 return CallbackReturn::SUCCESS;
120 }
121
122
123} // frame_transformer
124
125#include "rclcpp_components/register_node_macro.hpp"
126
127// Register the component with class_loader
128RCLCPP_COMPONENTS_REGISTER_NODE(frame_transformer::Node)
Node which subcribes to and input topic, transforms the data into a new frame and republishes it onto...
std::unique_ptr< TransformerBase > build_transformer()
Factory method which returns an initialized pointer to a TransformerBase.
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &)
std::shared_ptr< tf2_ros::Buffer > buffer_
tf2 Buffer to store transforms broadcast on the system
Config config_
Node configuration.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
std::unique_ptr< TransformerBase > transformer_
Pointer to a transformer which will setup its own pub/subs to perform the transformation
std::shared_ptr< tf2_ros::TransformListener > listener_
tf2 Listener to subscribe to system transform broadcasts
Node(const rclcpp::NodeOptions &)
Node constructor.
Stuct containing the algorithm configuration values for frame_transformer.
int timeout
Timeout in ms for transform lookup. A value of 0 means lookup will occur once without blocking if it ...
std::string target_frame
The target coordinate frame id to transform data into.
int queue_size
Queue size for publishers and subscribers.
std::string message_type
Message type which will be transformed.