SMACC2
cv_mat_sensor_msgs_image_type_adapter.hpp
Go to the documentation of this file.
1// Copyright 2021 Open Source Robotics Foundation, Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef IMAGE_TOOLS__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_
16#define IMAGE_TOOLS__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_
17
18#include <cstddef>
19#include <memory>
20#include <variant> // NOLINT[build/include_order]
21
22#include "opencv2/core/mat.hpp"
23
24#ifdef ROS_ROLLING
25#include "rclcpp/type_adapter.hpp"
26#include "image_tools/visibility_control.h"
27
28#else
29#include "type_adapter.hpp"
30#include "visibility_control.h"
31
32#endif
33
34#include "sensor_msgs/msg/image.hpp"
35
36
37namespace image_tools
38{
39namespace detail
40{
41// TODO(audrow): Replace with std::endian when C++ 20 is available
42// https://en.cppreference.com/w/cpp/types/endian
43enum class endian
44{
45#ifdef _WIN32
46 little = 0,
47 big = 1,
49#else
50 little = __ORDER_LITTLE_ENDIAN__,
51 big = __ORDER_BIG_ENDIAN__,
52 native = __BYTE_ORDER__
53#endif
54};
55
56} // namespace detail
57
58
59// TODO(wjwwood): make this as a contribution to vision_opencv's cv_bridge package.
60// Specifically the CvImage class, which is this is most similar to.
62
95{
97
98public:
99 using SensorMsgsImageStorageType = std::variant<
100 std::nullptr_t,
101 std::unique_ptr<sensor_msgs::msg::Image>,
102 std::shared_ptr<sensor_msgs::msg::Image>
103 >;
104
106 ROSCvMatContainer() = default;
107
109 explicit ROSCvMatContainer(const ROSCvMatContainer & other)
110 : header_(other.header_), frame_(other.frame_.clone()), is_bigendian_(other.is_bigendian_)
111 {
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_));
117 }
118 }
119
122 {
123 if (this != &other) {
124 header_ = other.header_;
125 frame_ = other.frame_.clone();
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_)) {
133 storage_ = nullptr;
134 }
135 }
136 return *this;
137 }
138
141 explicit ROSCvMatContainer(std::unique_ptr<sensor_msgs::msg::Image> unique_sensor_msgs_image);
142
145 explicit ROSCvMatContainer(std::shared_ptr<sensor_msgs::msg::Image> shared_sensor_msgs_image);
146
150 const cv::Mat & mat_frame,
151 const std_msgs::msg::Header & header,
153
157 cv::Mat && mat_frame,
158 const std_msgs::msg::Header & header,
160
163 explicit ROSCvMatContainer(const sensor_msgs::msg::Image & sensor_msgs_image);
164
166
171 bool
172 is_owning() const;
173
176 const cv::Mat &
177 cv_mat() const;
178
180
185 cv::Mat
186 cv_mat();
187
190 const std_msgs::msg::Header &
191 header() const;
192
195 std_msgs::msg::Header &
196 header();
197
200 std::shared_ptr<const sensor_msgs::msg::Image>
202
205 std::unique_ptr<sensor_msgs::msg::Image>
207
210 sensor_msgs::msg::Image
212
215 void
216 get_sensor_msgs_msg_image_copy(sensor_msgs::msg::Image & sensor_msgs_image) const;
217
220 bool
221 is_bigendian() const;
222
223private:
224 std_msgs::msg::Header header_;
225 cv::Mat frame_;
228};
229
230} // namespace image_tools
231
232template<>
233struct rclcpp::TypeAdapter<image_tools::ROSCvMatContainer, sensor_msgs::msg::Image>
234{
235 using is_specialized = std::true_type;
237 using ros_message_type = sensor_msgs::msg::Image;
238
239 static
240 void
242 const custom_type & source,
243 ros_message_type & destination)
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 }
269
270 static
271 void
273 const ros_message_type & source,
274 custom_type & destination)
275 {
276 destination = image_tools::ROSCvMatContainer(source);
277 }
278};
279
280#endif // IMAGE_TOOLS__CV_MAT_SENSOR_MSGS_IMAGE_TYPE_ADAPTER_HPP_
A potentially owning, potentially non-owning, container of a cv::Mat and ROS header.
IMAGE_TOOLS_PUBLIC sensor_msgs::msg::Image get_sensor_msgs_msg_image_copy() const
Get a copy of the image as a sensor_msgs::msg::Image.
IMAGE_TOOLS_PUBLIC bool is_bigendian() const
Return true if the data is stored in big endian, otherwise return false.
IMAGE_TOOLS_PUBLIC std::unique_ptr< sensor_msgs::msg::Image > get_sensor_msgs_msg_image_pointer_copy() const
Get copy as a unique pointer to the sensor_msgs::msg::Image.
IMAGE_TOOLS_PUBLIC bool is_owning() const
Return true if this class owns the data the cv_mat references.
IMAGE_TOOLS_PUBLIC ROSCvMatContainer & operator=(const ROSCvMatContainer &other)
IMAGE_TOOLS_PUBLIC ROSCvMatContainer(const ROSCvMatContainer &other)
IMAGE_TOOLS_PUBLIC std::shared_ptr< const sensor_msgs::msg::Image > get_sensor_msgs_msg_image_pointer() const
Get shared const pointer to the sensor_msgs::msg::Image if available, otherwise nullptr.
IMAGE_TOOLS_PUBLIC ROSCvMatContainer()=default
IMAGE_TOOLS_PUBLIC const std_msgs::msg::Header & header() const
Const access the ROS Header.
IMAGE_TOOLS_PUBLIC const cv::Mat & cv_mat() const
Const access the cv::Mat in this class.
std::variant< std::nullptr_t, std::unique_ptr< sensor_msgs::msg::Image >, std::shared_ptr< sensor_msgs::msg::Image > > SensorMsgsImageStorageType
static void convert_to_custom(const ros_message_type &source, custom_type &destination)
static void convert_to_ros_message(const custom_type &source, ros_message_type &destination)
Template structure used to adapt custom, user-defined types to ROS types.
#define IMAGE_TOOLS_PUBLIC