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 Class Reference

Node which subcribes to and input topic, transforms the data into a new frame and republishes it onto an output topic. More...

#include <frame_transformer_node.hpp>

Inheritance diagram for frame_transformer::Node:
Inheritance graph
Collaboration diagram for frame_transformer::Node:
Collaboration graph

Public Member Functions

 Node (const rclcpp::NodeOptions &)
 Node constructor. More...
 
std::unique_ptr< TransformerBasebuild_transformer ()
 Factory method which returns an initialized pointer to a TransformerBase. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 
carma_ros2_utils::CallbackReturn handle_on_cleanup (const rclcpp_lifecycle::State &)
 
 FRIEND_TEST (frame_transformer_test, transform_test)
 
 FRIEND_TEST (frame_transformer_test, point_cloud_transform_test)
 

Private Attributes

Config config_
 Node configuration. More...
 
std::unique_ptr< TransformerBasetransformer_
 Pointer to a transformer which will setup its own pub/subs to perform the transformation
More...
 
std::shared_ptr< tf2_ros::Buffer > buffer_
 tf2 Buffer to store transforms broadcast on the system More...
 
std::shared_ptr< tf2_ros::TransformListener > listener_
 tf2 Listener to subscribe to system transform broadcasts More...
 

Detailed Description

Node which subcribes to and input topic, transforms the data into a new frame and republishes it onto an output topic.

Definition at line 36 of file frame_transformer_node.hpp.

Constructor & Destructor Documentation

◆ Node()

frame_transformer::Node::Node ( const rclcpp::NodeOptions &  options)
explicit

Node constructor.

Definition at line 23 of file frame_transformer_node.cpp.

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 }
Config config_
Node configuration.
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.

References config_, frame_transformer::Config::message_type, frame_transformer::Config::queue_size, frame_transformer::Config::target_frame, and frame_transformer::Config::timeout.

Member Function Documentation

◆ build_transformer()

std::unique_ptr< TransformerBase > frame_transformer::Node::build_transformer ( )

Factory method which returns an initialized pointer to a TransformerBase.

ASSUMPTION: this->config_ and this->buffer_ are already initialized

Returns
Initialized pointer to a TransformBase object which contains the required pub/sub for transformations to occur

Definition at line 36 of file frame_transformer_node.cpp.

36 {
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 }
std::shared_ptr< tf2_ros::Buffer > buffer_
tf2 Buffer to store transforms broadcast on the system

References buffer_, config_, and frame_transformer::Config::message_type.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ FRIEND_TEST() [1/2]

frame_transformer::Node::FRIEND_TEST ( frame_transformer_test  ,
point_cloud_transform_test   
)

◆ FRIEND_TEST() [2/2]

frame_transformer::Node::FRIEND_TEST ( frame_transformer_test  ,
transform_test   
)

◆ handle_on_cleanup()

carma_ros2_utils::CallbackReturn frame_transformer::Node::handle_on_cleanup ( const rclcpp_lifecycle::State &  )

Definition at line 113 of file frame_transformer_node.cpp.

113 {
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 }
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

References buffer_, listener_, and transformer_.

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn frame_transformer::Node::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 75 of file frame_transformer_node.cpp.

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 }
std::unique_ptr< TransformerBase > build_transformer()
Factory method which returns an initialized pointer to a TransformerBase.

References buffer_, build_transformer(), config_, listener_, frame_transformer::Config::message_type, frame_transformer::Config::queue_size, frame_transformer::Config::target_frame, frame_transformer::Config::timeout, and transformer_.

Here is the call graph for this function:

Member Data Documentation

◆ buffer_

std::shared_ptr<tf2_ros::Buffer> frame_transformer::Node::buffer_
private

tf2 Buffer to store transforms broadcast on the system

Definition at line 48 of file frame_transformer_node.hpp.

Referenced by build_transformer(), handle_on_cleanup(), and handle_on_configure().

◆ config_

Config frame_transformer::Node::config_
private

Node configuration.

Definition at line 42 of file frame_transformer_node.hpp.

Referenced by Node(), build_transformer(), and handle_on_configure().

◆ listener_

std::shared_ptr<tf2_ros::TransformListener> frame_transformer::Node::listener_
private

tf2 Listener to subscribe to system transform broadcasts

Definition at line 51 of file frame_transformer_node.hpp.

Referenced by handle_on_cleanup(), and handle_on_configure().

◆ transformer_

std::unique_ptr<TransformerBase> frame_transformer::Node::transformer_
private

Pointer to a transformer which will setup its own pub/subs to perform the transformation

Definition at line 45 of file frame_transformer_node.hpp.

Referenced by handle_on_cleanup(), and handle_on_configure().


The documentation for this class was generated from the following files: