Class ROSCvMatContainer

Class Documentation

class ROSCvMatContainer

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 recieving 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:

  • template<typename _Tp > cv::Mat::Mat(const std::vector<_Tp> &, bool)

  • Mat & cv::Mat::operator=(const Mat &)

  • void cv::Mat::addref()

  • void cv::Mat::release()

Public Types

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

Public Functions

ROSCvMatContainer() = default
inline explicit ROSCvMatContainer(const ROSCvMatContainer &other)
inline ROSCvMatContainer &operator=(const ROSCvMatContainer &other)
explicit 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.

explicit 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.

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.

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.

explicit 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.

bool 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.

const cv::Mat &cv_mat() const

Const access the cv::Mat in this class.

cv::Mat 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.

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

Const access the ROS Header.

std_msgs::msg::Header &header()

Access the ROS Header.

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.

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.

sensor_msgs::msg::Image get_sensor_msgs_msg_image_copy() const

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

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.

bool is_bigendian() const

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