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.
|
Class template for data transformers which use the tf2_ros::Buffer.transform() method to perform transforms on ros messages. The class sets up publishers and subscribers using the provided node for the specified message type. The specified message type must have a tf2_ros::Buffer.doTransform specialization for its type in order for it to compile. More...
#include <frame_transformer.hpp>
Public Member Functions | |
Transformer (Config config, std::shared_ptr< tf2_ros::Buffer > buffer, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node) | |
Constructor which sets up the required publishers and subscribers. More... | |
bool | transform (const T &in, T &out, const std::string &target_frame, const std_ms timeout) |
Helper method which takes in an input message and transforms it to the provided frame. Returns false if the provided timeout is exceeded for getting the transform or the transform could not be computed. More... | |
void | input_callback (std::unique_ptr< T > in_msg) |
Callback for input data. Transforms the data then republishes it. More... | |
FRIEND_TEST (frame_transformer_test, transform_test) | |
void | input_callback (std::unique_ptr< sensor_msgs::msg::PointCloud2 > in_msg) |
Protected Attributes | |
carma_ros2_utils::SubPtr< T > | input_sub_ |
carma_ros2_utils::PubPtr< T > | output_pub_ |
![]() | |
Config | config_ |
Transformation configuration. More... | |
std::shared_ptr< tf2_ros::Buffer > | buffer_ |
TF2 Buffer for storing transform history and looking up transforms. More... | |
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > | node_ |
Containing node which provides access to the ros network. More... | |
Additional Inherited Members | |
![]() | |
TransformerBase (const Config &config, std::shared_ptr< tf2_ros::Buffer > buffer, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node) | |
Class template for data transformers which use the tf2_ros::Buffer.transform() method to perform transforms on ros messages. The class sets up publishers and subscribers using the provided node for the specified message type. The specified message type must have a tf2_ros::Buffer.doTransform specialization for its type in order for it to compile.
The | message type to transform. Must be supported by tf2_ros::Buffer.doTransform |
Definition at line 43 of file frame_transformer.hpp.
|
inline |
Constructor which sets up the required publishers and subscribers.
See comments in TransformerBase for parameter descriptions
Definition at line 61 of file frame_transformer.hpp.
References frame_transformer::TransformerBase::config_, frame_transformer::Transformer< T >::input_callback(), frame_transformer::Transformer< T >::input_sub_, frame_transformer::TransformerBase::node_, frame_transformer::Transformer< T >::output_pub_, and frame_transformer::Config::queue_size.
frame_transformer::Transformer< T >::FRIEND_TEST | ( | frame_transformer_test | , |
transform_test | |||
) |
|
inline |
Definition at line 130 of file frame_transformer.hpp.
|
inline |
Callback for input data. Transforms the data then republishes it.
NOTE: This method can be specialized for unique preallocation approaches for large messages such as point clouds or images
in_msg | The input message to transform |
Definition at line 111 of file frame_transformer.hpp.
References frame_transformer::TransformerBase::config_, frame_transformer::Transformer< T >::output_pub_, frame_transformer::Config::target_frame, frame_transformer::Config::timeout, and frame_transformer::Transformer< T >::transform().
Referenced by frame_transformer::Transformer< T >::Transformer().
|
inline |
Helper method which takes in an input message and transforms it to the provided frame. Returns false if the provided timeout is exceeded for getting the transform or the transform could not be computed.
in | The input message to transform | |
[out] | out | The preallocated location for the output message |
target_frame | The frame the out message data will be in | |
timeout | A timeout in ms which if exceeded will result in a false return and invalid out value. This call may block for this period. If set to zero, then lookup will be attempted only once. |
Definition at line 84 of file frame_transformer.hpp.
References frame_transformer::TransformerBase::buffer_, and frame_transformer::TransformerBase::node_.
Referenced by frame_transformer::Transformer< T >::input_callback().
|
protected |
Definition at line 48 of file frame_transformer.hpp.
Referenced by frame_transformer::Transformer< T >::Transformer().
|
protected |
Definition at line 51 of file frame_transformer.hpp.
Referenced by frame_transformer::Transformer< T >::Transformer(), and frame_transformer::Transformer< T >::input_callback().