diff --git a/image_tools/include/image_tools/cv_mat_sensor_msgs_image_type_adapter.hpp b/image_tools/include/image_tools/cv_mat_sensor_msgs_image_type_adapter.hpp index ea3a772d2..04875b110 100644 --- a/image_tools/include/image_tools/cv_mat_sensor_msgs_image_type_adapter.hpp +++ b/image_tools/include/image_tools/cv_mat_sensor_msgs_image_type_adapter.hpp @@ -97,32 +97,33 @@ class ROSCvMatContainer ROSCvMatContainer() = default; IMAGE_TOOLS_PUBLIC - explicit ROSCvMatContainer(const ROSCvMatContainer &other) : - header_(other.header_), frame_(other.frame_), is_bigendian_(other.is_bigendian_) - { - if(std::holds_alternative>(other.storage_)) { + explicit ROSCvMatContainer(const ROSCvMatContainer & other) + : header_(other.header_), frame_(other.frame_.clone()), is_bigendian_(other.is_bigendian_) + { + if (std::holds_alternative>(other.storage_)) { + storage_ = std::get>(other.storage_); + } else if (std::holds_alternative>(other.storage_)) { + storage_ = std::make_unique( + *std::get>(other.storage_)); + } + } + + IMAGE_TOOLS_PUBLIC + ROSCvMatContainer & operator=(const ROSCvMatContainer & other) + { + if (this != &other) { + header_ = other.header_; + frame_ = other.frame_.clone(); + is_bigendian_ = other.is_bigendian_; + if (std::holds_alternative>(other.storage_)) { storage_ = std::get>(other.storage_); + } else if (std::holds_alternative>(other.storage_)) { + storage_ = std::make_unique( + *std::get>(other.storage_)); } - else if(std::holds_alternative>(other.storage_)) { - storage_ = std::make_unique( *std::get>(other.storage_) ); - } - - }; - - ROSCvMatContainer& operator=(const ROSCvMatContainer& other){ - if (this != &other) { - header_ = other.header_; - frame_ = other.frame_; - is_bigendian_ = other.is_bigendian_; - if(std::holds_alternative>(other.storage_)) { - storage_ = std::get>(other.storage_); - } - else if(std::holds_alternative>(other.storage_)) { - storage_ = std::make_unique( *std::get>(other.storage_) ); - } - } - return *this; - } + } + return *this; + } /// Store an owning pointer to a sensor_msg::msg::Image, and create a cv::Mat that references it. IMAGE_TOOLS_PUBLIC