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.
|
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>
Public Member Functions | |
Node (const rclcpp::NodeOptions &) | |
Node constructor. More... | |
std::unique_ptr< TransformerBase > | build_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< TransformerBase > | transformer_ |
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... | |
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.
|
explicit |
Node constructor.
Definition at line 23 of file frame_transformer_node.cpp.
References config_, frame_transformer::Config::message_type, frame_transformer::Config::queue_size, frame_transformer::Config::target_frame, and frame_transformer::Config::timeout.
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
Definition at line 36 of file frame_transformer_node.cpp.
References buffer_, config_, and frame_transformer::Config::message_type.
Referenced by handle_on_configure().
frame_transformer::Node::FRIEND_TEST | ( | frame_transformer_test | , |
point_cloud_transform_test | |||
) |
frame_transformer::Node::FRIEND_TEST | ( | frame_transformer_test | , |
transform_test | |||
) |
carma_ros2_utils::CallbackReturn frame_transformer::Node::handle_on_cleanup | ( | const rclcpp_lifecycle::State & | ) |
Definition at line 113 of file frame_transformer_node.cpp.
References buffer_, listener_, and transformer_.
carma_ros2_utils::CallbackReturn frame_transformer::Node::handle_on_configure | ( | const rclcpp_lifecycle::State & | ) |
Definition at line 75 of file frame_transformer_node.cpp.
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_.
|
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().
|
private |
Node configuration.
Definition at line 42 of file frame_transformer_node.hpp.
Referenced by Node(), build_transformer(), and handle_on_configure().
|
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().
|
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().