SMACC2
Public Types | Static Public Member Functions | List of all members
rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image > Struct Reference

#include <cv_mat_sensor_msgs_image_type_adapter.hpp>

Collaboration diagram for rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >:
Collaboration graph

Public Types

using is_specialized = std::true_type
 
using custom_type = image_tools::ROSCvMatContainer
 
using ros_message_type = sensor_msgs::msg::Image
 

Static Public Member Functions

static void convert_to_ros_message (const custom_type &source, ros_message_type &destination)
 
static void convert_to_custom (const ros_message_type &source, custom_type &destination)
 

Detailed Description

Definition at line 233 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

Member Typedef Documentation

◆ custom_type

using rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::custom_type = image_tools::ROSCvMatContainer

Definition at line 236 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

◆ is_specialized

using rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::is_specialized = std::true_type

Definition at line 235 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

◆ ros_message_type

using rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::ros_message_type = sensor_msgs::msg::Image

Definition at line 237 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

Member Function Documentation

◆ convert_to_custom()

static void rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::convert_to_custom ( const ros_message_type source,
custom_type destination 
)
inlinestatic

Definition at line 272 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

275 {
276 destination = image_tools::ROSCvMatContainer(source);
277 }
A potentially owning, potentially non-owning, container of a cv::Mat and ROS header.

◆ convert_to_ros_message()

static void rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::convert_to_ros_message ( const custom_type source,
ros_message_type destination 
)
inlinestatic

Definition at line 241 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

244 {
245 destination.height = source.cv_mat().rows;
246 destination.width = source.cv_mat().cols;
247 switch (source.cv_mat().type()) {
248 case CV_8UC1:
249 destination.encoding = "mono8";
250 break;
251 case CV_8UC3:
252 destination.encoding = "bgr8";
253 break;
254 case CV_16SC1:
255 destination.encoding = "mono16";
256 break;
257 case CV_8UC4:
258 destination.encoding = "rgba8";
259 break;
260 default:
261 throw std::runtime_error("unsupported encoding type");
262 }
263 destination.step = static_cast<sensor_msgs::msg::Image::_step_type>(source.cv_mat().step);
264 size_t size = source.cv_mat().step * source.cv_mat().rows;
265 destination.data.resize(size);
266 memcpy(&destination.data[0], source.cv_mat().data, size);
267 destination.header = source.header();
268 }

References image_tools::ROSCvMatContainer::cv_mat(), and image_tools::ROSCvMatContainer::header().

Here is the call graph for this function:

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