15#ifndef IMAGE_TOOLS__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_
16#define IMAGE_TOOLS__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_
22#include "opencv2/core/mat.hpp"
25#include "rclcpp/type_adapter.hpp"
26#include "image_tools/visibility_control.h"
34#include "sensor_msgs/msg/image.hpp"
50 little = __ORDER_LITTLE_ENDIAN__,
51 big = __ORDER_BIG_ENDIAN__,
101 std::unique_ptr<sensor_msgs::msg::Image>,
102 std::shared_ptr<sensor_msgs::msg::Image>
112 if (std::holds_alternative<std::shared_ptr<sensor_msgs::msg::Image>>(other.
storage_)) {
113 storage_ = std::get<std::shared_ptr<sensor_msgs::msg::Image>>(other.
storage_);
114 }
else if (std::holds_alternative<std::unique_ptr<sensor_msgs::msg::Image>>(other.
storage_)) {
115 storage_ = std::make_unique<sensor_msgs::msg::Image>(
116 *std::get<std::unique_ptr<sensor_msgs::msg::Image>>(other.
storage_));
123 if (
this != &other) {
127 if (std::holds_alternative<std::shared_ptr<sensor_msgs::msg::Image>>(other.
storage_)) {
128 storage_ = std::get<std::shared_ptr<sensor_msgs::msg::Image>>(other.
storage_);
129 }
else if (std::holds_alternative<std::unique_ptr<sensor_msgs::msg::Image>>(other.
storage_)) {
130 storage_ = std::make_unique<sensor_msgs::msg::Image>(
131 *std::get<std::unique_ptr<sensor_msgs::msg::Image>>(other.
storage_));
132 }
else if (std::holds_alternative<std::nullptr_t>(other.
storage_)) {
141 explicit ROSCvMatContainer(std::unique_ptr<sensor_msgs::msg::Image> unique_sensor_msgs_image);
145 explicit ROSCvMatContainer(std::shared_ptr<sensor_msgs::msg::Image> shared_sensor_msgs_image);
150 const cv::Mat & mat_frame,
151 const std_msgs::msg::Header &
header,
157 cv::Mat && mat_frame,
158 const std_msgs::msg::Header &
header,
190 const std_msgs::msg::Header &
195 std_msgs::msg::Header &
200 std::shared_ptr<const sensor_msgs::msg::Image>
205 std::unique_ptr<sensor_msgs::msg::Image>
210 sensor_msgs::msg::Image
245 destination.height = source.
cv_mat().rows;
246 destination.width = source.
cv_mat().cols;
247 switch (source.
cv_mat().type()) {
249 destination.encoding =
"mono8";
252 destination.encoding =
"bgr8";
255 destination.encoding =
"mono16";
258 destination.encoding =
"rgba8";
261 throw std::runtime_error(
"unsupported encoding type");
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();
Template structure used to adapt custom, user-defined types to ROS types.
#define IMAGE_TOOLS_PUBLIC