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::Transformer< T > Class Template Reference

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>

Inheritance diagram for frame_transformer::Transformer< T >:
Inheritance graph
Collaboration diagram for frame_transformer::Transformer< T >:
Collaboration graph

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_
 
- Protected Attributes inherited from frame_transformer::TransformerBase
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

- Protected Member Functions inherited from frame_transformer::TransformerBase
 TransformerBase (const Config &config, std::shared_ptr< tf2_ros::Buffer > buffer, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node)
 

Detailed Description

template<class T>
class frame_transformer::Transformer< T >

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.

Template Parameters
Themessage type to transform. Must be supported by tf2_ros::Buffer.doTransform

Definition at line 43 of file frame_transformer.hpp.

Constructor & Destructor Documentation

◆ Transformer()

template<class T >
frame_transformer::Transformer< T >::Transformer ( Config  config,
std::shared_ptr< tf2_ros::Buffer >  buffer,
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode >  node 
)
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.

62 : TransformerBase(config, buffer, node) {
63
64 input_sub_ = node_->create_subscription<T>("input", config_.queue_size,
65 std::bind(&Transformer::input_callback, this, std_ph::_1));
66
67 // Setup publishers
68 output_pub_ = node_->create_publisher<T>("output", config_.queue_size);
69 }
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node_
Containing node which provides access to the ros network.
Config config_
Transformation configuration.
TransformerBase(const Config &config, std::shared_ptr< tf2_ros::Buffer > buffer, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > node)
carma_ros2_utils::SubPtr< T > input_sub_
void input_callback(std::unique_ptr< T > in_msg)
Callback for input data. Transforms the data then republishes it.
carma_ros2_utils::PubPtr< T > output_pub_
int queue_size
Queue size for publishers and subscribers.

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.

Here is the call graph for this function:

Member Function Documentation

◆ FRIEND_TEST()

template<class T >
frame_transformer::Transformer< T >::FRIEND_TEST ( frame_transformer_test  ,
transform_test   
)

◆ input_callback() [1/2]

void frame_transformer::Transformer< sensor_msgs::msg::PointCloud2 >::input_callback ( std::unique_ptr< sensor_msgs::msg::PointCloud2 >  in_msg)
inline

Definition at line 130 of file frame_transformer.hpp.

130 {
131
132 sensor_msgs::msg::PointCloud2 out_msg;
133 out_msg.data.reserve(in_msg->data.size()); // Preallocate points vector
134
135
136 if (!transform(*in_msg, out_msg, config_.target_frame, std_ms(config_.timeout)))
137 {
138 return;
139 }
140
141 // The following if block is added purely for ensuring consistency with Autoware.Auto (prevent "Malformed PointCloud2" error from ray_ground_filter)
142 // It's a bit out of scope for this node to have this functionality here,
143 // but the alternative is to modify a 3rd party driver, an Autoware.Auto component, or make a new node just for this.
144 // Therefore, the logic will live here until such a time as a better location presents itself.
145 if (out_msg.height == 1) // 1d point cloud
146 {
147 out_msg.row_step = out_msg.data.size();
148 }
149
150 output_pub_->publish(out_msg);
151 }
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....
std::chrono::milliseconds std_ms
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.

◆ input_callback() [2/2]

template<class T >
void frame_transformer::Transformer< T >::input_callback ( std::unique_ptr< T >  in_msg)
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

Parameters
in_msgThe input message to transform

Definition at line 111 of file frame_transformer.hpp.

112 {
113 T out_msg;
114
115 if (!transform(*in_msg, out_msg, config_.target_frame, std_ms(config_.timeout)))
116 {
117 return;
118 }
119
120 output_pub_->publish(out_msg);
121 }

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ transform()

template<class T >
bool frame_transformer::Transformer< T >::transform ( const T &  in,
T &  out,
const std::string &  target_frame,
const std_ms  timeout 
)
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.

Parameters
inThe input message to transform
[out]outThe preallocated location for the output message
target_frameThe frame the out message data will be in
timeoutA 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.
Returns
True if transform succeeded, false if timeout exceeded or transform could not be performed.

Definition at line 84 of file frame_transformer.hpp.

85 {
86
87 try
88 {
89 buffer_->transform(in, out, target_frame, timeout);
90 }
91 catch (tf2::TransformException &ex)
92 {
93 std::string error = ex.what();
94 error = "Failed to get transform with exception: " + error;
95 auto& clk = *node_->get_clock(); // Separate reference required for proper throttle macro call
96 RCLCPP_WARN_THROTTLE(node_->get_logger(), clk, 1000, error.c_str());
97
98 return false;
99 }
100
101 return true;
102 }
std::shared_ptr< tf2_ros::Buffer > buffer_
TF2 Buffer for storing transform history and looking up transforms.

References frame_transformer::TransformerBase::buffer_, and frame_transformer::TransformerBase::node_.

Referenced by frame_transformer::Transformer< T >::input_callback().

Here is the caller graph for this function:

Member Data Documentation

◆ input_sub_

template<class T >
carma_ros2_utils::SubPtr<T> frame_transformer::Transformer< T >::input_sub_
protected

◆ output_pub_

template<class T >
carma_ros2_utils::PubPtr<T> frame_transformer::Transformer< T >::output_pub_
protected

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