diff --git a/cv_bridge/include/cv_bridge/cv_bridge.h b/cv_bridge/include/cv_bridge/cv_bridge.h index 60f8bfabb..759df0200 100644 --- a/cv_bridge/include/cv_bridge/cv_bridge.h +++ b/cv_bridge/include/cv_bridge/cv_bridge.h @@ -117,10 +117,24 @@ class CV_BRIDGE_EXPORT CvImage * can be: jpg, jp2, bmp, png, tif at the moment * support this format from opencv: * http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags) + * params are the options for cv::imencode. + * Default value is empty list. */ sensor_msgs::msg::CompressedImage::SharedPtr toCompressedImageMsg( - const Format dst_format = - JPG) const; + const Format dst_format = JPG, + const std::vector ¶ms=std::vector()) const; + + /** + * dst_format is compress the image to desire format. + * Default value is empty string that will convert to jpg format. + * can be: jpg, jp2, bmp, png, tif at the moment + * support this format from opencv: + * http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags) + * params are the options for cv::imencode. + * Default value is empty list. + */ + sensor_msgs::msg::CompressedImage::SharedPtr toCompressedImageMsg( + const std::vector ¶ms=std::vector(), const Format dst_format = JPG) const; /** * \brief Copy the message data to a ROS sensor_msgs::msg::Image message. @@ -136,11 +150,25 @@ class CV_BRIDGE_EXPORT CvImage * can be: jpg, jp2, bmp, png, tif at the moment * support this format from opencv: * http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags) + * params are the options for cv::imencode. + * Default value is empty list. */ void toCompressedImageMsg( sensor_msgs::msg::CompressedImage & ros_image, - const Format dst_format = JPG) const; + const Format dst_format = JPG, const std::vector ¶ms=std::vector()) const; + /** + * dst_format is compress the image to desire format. + * Default value is empty string that will convert to jpg format. + * can be: jpg, jp2, bmp, png, tif at the moment + * support this format from opencv: + * http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags) + * params are the options for cv::imencode. + * Default value is empty list. + */ + void toCompressedImageMsg( + sensor_msgs::msg::CompressedImage & ros_image, + const std::vector ¶ms=std::vector(), const Format dst_format = JPG) const; typedef std::shared_ptr Ptr; typedef std::shared_ptr ConstPtr; diff --git a/cv_bridge/src/cv_bridge.cpp b/cv_bridge/src/cv_bridge.cpp index 0a2e4f577..611954af5 100644 --- a/cv_bridge/src/cv_bridge.cpp +++ b/cv_bridge/src/cv_bridge.cpp @@ -464,15 +464,21 @@ CvImagePtr cvtColor( /////////////////////////////////////// CompressedImage /////////////////////////////////////////// -sensor_msgs::msg::CompressedImage::SharedPtr CvImage::toCompressedImageMsg(const Format dst_format) +sensor_msgs::msg::CompressedImage::SharedPtr CvImage::toCompressedImageMsg(const Format dst_format,const std::vector ¶ms) const { sensor_msgs::msg::CompressedImage::SharedPtr ptr = std::make_shared(); - toCompressedImageMsg(*ptr, dst_format); + toCompressedImageMsg(*ptr, dst_format, params); return ptr; } +sensor_msgs::msg::CompressedImage::SharedPtr CvImage::toCompressedImageMsg(const std::vector ¶ms, const Format dst_format) +const +{ + return toCompressedImageMsg(dst_format, params); +} + std::string getFormat(Format format) { switch (format) { @@ -511,7 +517,14 @@ std::string getFormat(Format format) void CvImage::toCompressedImageMsg( sensor_msgs::msg::CompressedImage & ros_image, - const Format dst_format) const + const std::vector ¶ms, const Format dst_format) const +{ + toCompressedImageMsg(ros_image, dst_format, params); +} + +void CvImage::toCompressedImageMsg( + sensor_msgs::msg::CompressedImage & ros_image, + const Format dst_format, const std::vector ¶ms) const { ros_image.header = header; cv::Mat image; @@ -531,7 +544,7 @@ void CvImage::toCompressedImageMsg( std::string format = getFormat(dst_format); ros_image.format = format; - cv::imencode("." + format, image, ros_image.data); + cv::imencode("." + format, image, ros_image.data, params); } // Deep copy data, returnee is mutable