SMACC2
Public Types | Public Member Functions | Private Attributes | Static Private Attributes | List of all members
image_tools::ROSCvMatContainer Class Reference

A potentially owning, potentially non-owning, container of a cv::Mat and ROS header. More...

#include <cv_mat_sensor_msgs_image_type_adapter.hpp>

Collaboration diagram for image_tools::ROSCvMatContainer:
Collaboration graph

Public Types

using SensorMsgsImageStorageType = std::variant< std::nullptr_t, std::unique_ptr< sensor_msgs::msg::Image >, std::shared_ptr< sensor_msgs::msg::Image > >
 

Public Member Functions

IMAGE_TOOLS_PUBLIC ROSCvMatContainer ()=default
 
IMAGE_TOOLS_PUBLIC ROSCvMatContainer (const ROSCvMatContainer &other)
 
IMAGE_TOOLS_PUBLIC ROSCvMatContaineroperator= (const ROSCvMatContainer &other)
 
IMAGE_TOOLS_PUBLIC ROSCvMatContainer (std::unique_ptr< sensor_msgs::msg::Image > unique_sensor_msgs_image)
 Store an owning pointer to a sensor_msg::msg::Image, and create a cv::Mat that references it. More...
 
IMAGE_TOOLS_PUBLIC ROSCvMatContainer (std::shared_ptr< sensor_msgs::msg::Image > shared_sensor_msgs_image)
 Store an owning pointer to a sensor_msg::msg::Image, and create a cv::Mat that references it. More...
 
IMAGE_TOOLS_PUBLIC ROSCvMatContainer (const cv::Mat &mat_frame, const std_msgs::msg::Header &header, bool is_bigendian=is_bigendian_system)
 Shallow copy the given cv::Mat into this class, but do not own the data directly. More...
 
IMAGE_TOOLS_PUBLIC ROSCvMatContainer (cv::Mat &&mat_frame, const std_msgs::msg::Header &header, bool is_bigendian=is_bigendian_system)
 Move the given cv::Mat into this class. More...
 
IMAGE_TOOLS_PUBLIC ROSCvMatContainer (const sensor_msgs::msg::Image &sensor_msgs_image)
 Copy the sensor_msgs::msg::Image into this contain and create a cv::Mat that references it. More...
 
IMAGE_TOOLS_PUBLIC bool is_owning () const
 Return true if this class owns the data the cv_mat references. More...
 
IMAGE_TOOLS_PUBLIC const cv::Mat & cv_mat () const
 Const access the cv::Mat in this class. More...
 
IMAGE_TOOLS_PUBLIC cv::Mat cv_mat ()
 Get a shallow copy of the cv::Mat that is in this class. More...
 
IMAGE_TOOLS_PUBLIC const std_msgs::msg::Header & header () const
 Const access the ROS Header. More...
 
IMAGE_TOOLS_PUBLIC std_msgs::msg::Header & header ()
 Access the ROS Header. More...
 
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. More...
 
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. More...
 
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. More...
 
IMAGE_TOOLS_PUBLIC void get_sensor_msgs_msg_image_copy (sensor_msgs::msg::Image &sensor_msgs_image) const
 Get a copy of the image as a sensor_msgs::msg::Image. More...
 
IMAGE_TOOLS_PUBLIC bool is_bigendian () const
 Return true if the data is stored in big endian, otherwise return false. More...
 

Private Attributes

std_msgs::msg::Header header_
 
cv::Mat frame_
 
SensorMsgsImageStorageType storage_
 
bool is_bigendian_
 

Static Private Attributes

static constexpr bool is_bigendian_system = detail::endian::native == detail::endian::big
 

Detailed Description

A potentially owning, potentially non-owning, container of a cv::Mat and ROS header.

The two main use cases for this are publishing user controlled data, and receiving data from the middleware that may have been a ROS message originally or may have been an cv::Mat originally.

In the first case, publishing user owned data, the user will want to provide their own cv::Mat. The cv::Mat may own the data or it may not, so in the latter case, it is up to the user to ensure the data the cv::Mat points to remains valid as long as the middleware needs it.

In the second case, receiving data from the middleware, the middleware will either give a new ROSCvMatContainer which owns a sensor_msgs::msg::Image or it will give a ROSCvMatContainer that was previously published by the user (in the case of intra-process communication). If the container owns the sensor_msgs::msg::Image, then the cv::Mat will just reference data field of this message, so the container needs to be kept. If the container was published by the user it may or may not own the data and the cv::Mat it contains may or may not own the data.

For these reasons, it is advisable to use cv::Mat::clone() if you intend to copy the cv::Mat and let this container go.

For more details about the ownership behavior of cv::Mat see documentation for these methods of cv::Mat:

Definition at line 94 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

Member Typedef Documentation

◆ SensorMsgsImageStorageType

using image_tools::ROSCvMatContainer::SensorMsgsImageStorageType = std::variant< std::nullptr_t, std::unique_ptr<sensor_msgs::msg::Image>, std::shared_ptr<sensor_msgs::msg::Image> >

Definition at line 99 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

Constructor & Destructor Documentation

◆ ROSCvMatContainer() [1/7]

IMAGE_TOOLS_PUBLIC image_tools::ROSCvMatContainer::ROSCvMatContainer ( )
default

◆ ROSCvMatContainer() [2/7]

IMAGE_TOOLS_PUBLIC image_tools::ROSCvMatContainer::ROSCvMatContainer ( const ROSCvMatContainer other)
inlineexplicit

Definition at line 109 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

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 }

References storage_.

◆ ROSCvMatContainer() [3/7]

image_tools::ROSCvMatContainer::ROSCvMatContainer ( std::unique_ptr< sensor_msgs::msg::Image >  unique_sensor_msgs_image)
explicit

Store an owning pointer to a sensor_msg::msg::Image, and create a cv::Mat that references it.

Definition at line 73 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

75: header_(NotNull(
76 unique_sensor_msgs_image.get(),
77 "unique_sensor_msgs_image cannot be nullptr"
78).pointer->header),
79 frame_(
80 unique_sensor_msgs_image->height,
81 unique_sensor_msgs_image->width,
82 encoding2mat_type(unique_sensor_msgs_image->encoding),
83 unique_sensor_msgs_image->data.data(),
84 unique_sensor_msgs_image->step),
85 storage_(std::move(unique_sensor_msgs_image))
86{}

◆ ROSCvMatContainer() [4/7]

image_tools::ROSCvMatContainer::ROSCvMatContainer ( std::shared_ptr< sensor_msgs::msg::Image >  shared_sensor_msgs_image)
explicit

Store an owning pointer to a sensor_msg::msg::Image, and create a cv::Mat that references it.

Definition at line 88 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

90: header_(shared_sensor_msgs_image->header),
91 frame_(
92 shared_sensor_msgs_image->height,
93 shared_sensor_msgs_image->width,
94 encoding2mat_type(shared_sensor_msgs_image->encoding),
95 shared_sensor_msgs_image->data.data(),
96 shared_sensor_msgs_image->step),
97 storage_(shared_sensor_msgs_image)
98{}

◆ ROSCvMatContainer() [5/7]

image_tools::ROSCvMatContainer::ROSCvMatContainer ( const cv::Mat &  mat_frame,
const std_msgs::msg::Header &  header,
bool  is_bigendian = is_bigendian_system 
)

Shallow copy the given cv::Mat into this class, but do not own the data directly.

Definition at line 100 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

104: header_(header),
105 frame_(mat_frame),
106 storage_(nullptr),
108{}
IMAGE_TOOLS_PUBLIC bool is_bigendian() const
Return true if the data is stored in big endian, otherwise return false.
IMAGE_TOOLS_PUBLIC const std_msgs::msg::Header & header() const
Const access the ROS Header.

◆ ROSCvMatContainer() [6/7]

image_tools::ROSCvMatContainer::ROSCvMatContainer ( cv::Mat &&  mat_frame,
const std_msgs::msg::Header &  header,
bool  is_bigendian = is_bigendian_system 
)

Move the given cv::Mat into this class.

Definition at line 110 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

114: header_(header),
115 frame_(std::forward<cv::Mat>(mat_frame)),
116 storage_(nullptr),
118{}

◆ ROSCvMatContainer() [7/7]

image_tools::ROSCvMatContainer::ROSCvMatContainer ( const sensor_msgs::msg::Image &  sensor_msgs_image)
explicit

Copy the sensor_msgs::msg::Image into this contain and create a cv::Mat that references it.

Definition at line 120 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

122: ROSCvMatContainer(std::make_unique<sensor_msgs::msg::Image>(sensor_msgs_image))
123{}
IMAGE_TOOLS_PUBLIC ROSCvMatContainer()=default

Member Function Documentation

◆ cv_mat() [1/2]

cv::Mat image_tools::ROSCvMatContainer::cv_mat ( )

Get a shallow copy of the cv::Mat that is in this class.

Note that if you want to let this container go out of scope you should make a deep copy with cv::Mat::clone() beforehand.

Definition at line 138 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

139{
140 return frame_;
141}

References frame_.

◆ cv_mat() [2/2]

const cv::Mat & image_tools::ROSCvMatContainer::cv_mat ( ) const

Const access the cv::Mat in this class.

Definition at line 132 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

133{
134 return frame_;
135}

References frame_.

Referenced by callback(), and rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::convert_to_ros_message().

Here is the caller graph for this function:

◆ get_sensor_msgs_msg_image_copy() [1/2]

IMAGE_TOOLS_PUBLIC sensor_msgs::msg::Image image_tools::ROSCvMatContainer::get_sensor_msgs_msg_image_copy ( ) const

Get a copy of the image as a sensor_msgs::msg::Image.

Referenced by get_sensor_msgs_msg_image_pointer_copy().

Here is the caller graph for this function:

◆ get_sensor_msgs_msg_image_copy() [2/2]

void image_tools::ROSCvMatContainer::get_sensor_msgs_msg_image_copy ( sensor_msgs::msg::Image &  sensor_msgs_image) const

Get a copy of the image as a sensor_msgs::msg::Image.

Definition at line 173 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

175{
176 sensor_msgs_image.height = frame_.rows;
177 sensor_msgs_image.width = frame_.cols;
178 switch (frame_.type()) {
179 case CV_8UC1:
180 sensor_msgs_image.encoding = "mono8";
181 break;
182 case CV_8UC3:
183 sensor_msgs_image.encoding = "bgr8";
184 break;
185 case CV_16SC1:
186 sensor_msgs_image.encoding = "mono16";
187 break;
188 case CV_8UC4:
189 sensor_msgs_image.encoding = "rgba8";
190 break;
191 default:
192 throw std::runtime_error("unsupported encoding type");
193 }
194 sensor_msgs_image.step = static_cast<sensor_msgs::msg::Image::_step_type>(frame_.step);
195 size_t size = frame_.step * frame_.rows;
196 sensor_msgs_image.data.resize(size);
197 memcpy(&sensor_msgs_image.data[0], frame_.data, size);
198 sensor_msgs_image.header = header_;
199}

References frame_, and header_.

◆ get_sensor_msgs_msg_image_pointer()

std::shared_ptr< const sensor_msgs::msg::Image > image_tools::ROSCvMatContainer::get_sensor_msgs_msg_image_pointer ( ) const

Get shared const pointer to the sensor_msgs::msg::Image if available, otherwise nullptr.

Definition at line 156 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

157{
158 if (!std::holds_alternative<std::shared_ptr<sensor_msgs::msg::Image>>(storage_)) {
159 return nullptr;
160 }
161 return std::get<std::shared_ptr<sensor_msgs::msg::Image>>(storage_);
162}

References storage_.

◆ get_sensor_msgs_msg_image_pointer_copy()

std::unique_ptr< sensor_msgs::msg::Image > image_tools::ROSCvMatContainer::get_sensor_msgs_msg_image_pointer_copy ( ) const

Get copy as a unique pointer to the sensor_msgs::msg::Image.

Definition at line 165 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

166{
167 auto unique_image = std::make_unique<sensor_msgs::msg::Image>();
168 this->get_sensor_msgs_msg_image_copy(*unique_image);
169 return unique_image;
170}
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.

References get_sensor_msgs_msg_image_copy().

Here is the call graph for this function:

◆ header() [1/2]

std_msgs::msg::Header & image_tools::ROSCvMatContainer::header ( )

Access the ROS Header.

Definition at line 150 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

151{
152 return header_;
153}

References header_.

◆ header() [2/2]

const std_msgs::msg::Header & image_tools::ROSCvMatContainer::header ( ) const

Const access the ROS Header.

Definition at line 144 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

145{
146 return header_;
147}

References header_.

Referenced by callback(), and rclcpp::TypeAdapter< image_tools::ROSCvMatContainer, sensor_msgs::msg::Image >::convert_to_ros_message().

Here is the caller graph for this function:

◆ is_bigendian()

bool image_tools::ROSCvMatContainer::is_bigendian ( ) const

Return true if the data is stored in big endian, otherwise return false.

Definition at line 202 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

203{
204 return is_bigendian_;
205}

References is_bigendian_.

◆ is_owning()

bool image_tools::ROSCvMatContainer::is_owning ( ) const

Return true if this class owns the data the cv_mat references.

Note that this does not check if the cv::Mat owns its own data, only if this class owns a sensor_msgs::msg::Image that the cv::Mat references.

Definition at line 126 of file cv_mat_sensor_msgs_image_type_adapter.cpp.

127{
128 return std::holds_alternative<std::nullptr_t>(storage_);
129}

References storage_.

◆ operator=()

IMAGE_TOOLS_PUBLIC ROSCvMatContainer & image_tools::ROSCvMatContainer::operator= ( const ROSCvMatContainer other)
inline

Definition at line 121 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

122 {
123 if (this != &other) {
124 header_ = other.header_;
125 frame_ = other.frame_.clone();
126 is_bigendian_ = other.is_bigendian_;
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 }

References frame_, header_, is_bigendian_, and storage_.

Member Data Documentation

◆ frame_

cv::Mat image_tools::ROSCvMatContainer::frame_
private

◆ header_

std_msgs::msg::Header image_tools::ROSCvMatContainer::header_
private

◆ is_bigendian_

bool image_tools::ROSCvMatContainer::is_bigendian_
private

Definition at line 227 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

Referenced by is_bigendian(), and operator=().

◆ is_bigendian_system

constexpr bool image_tools::ROSCvMatContainer::is_bigendian_system = detail::endian::native == detail::endian::big
staticconstexprprivate

Definition at line 96 of file cv_mat_sensor_msgs_image_type_adapter.hpp.

◆ storage_

SensorMsgsImageStorageType image_tools::ROSCvMatContainer::storage_
private

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