diff --git a/compressed_image_transport/CMakeLists.txt b/compressed_image_transport/CMakeLists.txt index 7fe17ed..672add8 100644 --- a/compressed_image_transport/CMakeLists.txt +++ b/compressed_image_transport/CMakeLists.txt @@ -9,20 +9,24 @@ generate_dynamic_reconfigure_options(cfg/CompressedPublisher.cfg cfg/CompressedS catkin_package( INCLUDE_DIRS include - LIBRARIES ${PROJECT_NAME} + LIBRARIES ${PROJECT_NAME} ${PROJECT_NAME}_compression CATKIN_DEPENDS cv_bridge dynamic_reconfigure image_transport DEPENDS OpenCV ) include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}) +add_library(${PROJECT_NAME}_compression src/compression_common.cpp) +add_dependencies(${PROJECT_NAME}_compression ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME}_compression ${catkin_LIBRARIES} ${OpenCV_LIBRARIES}) + add_library(${PROJECT_NAME} src/compressed_publisher.cpp src/compressed_subscriber.cpp src/manifest.cpp) -add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg) -target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES}) +add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg ${PROJECT_NAME}_compression) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${PROJECT_NAME}_compression) class_loader_hide_library_symbols(${PROJECT_NAME}) -install(TARGETS ${PROJECT_NAME} +install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_compression ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} diff --git a/compressed_image_transport/include/compressed_image_transport/compression_common.h b/compressed_image_transport/include/compressed_image_transport/compression_common.h index a680a09..42bdb59 100644 --- a/compressed_image_transport/include/compressed_image_transport/compression_common.h +++ b/compressed_image_transport/include/compressed_image_transport/compression_common.h @@ -35,6 +35,9 @@ #ifndef COMPRESSED_IMAGE_TRANSPORT_COMPRESSION_COMMON #define COMPRESSED_IMAGE_TRANSPORT_COMPRESSION_COMMON +#include +#include + namespace compressed_image_transport { @@ -44,6 +47,19 @@ enum compressionFormat UNDEFINED = -1, JPEG, PNG }; +// standadlone decoding function +sensor_msgs::ImagePtr decodeCompressedImage(const sensor_msgs::CompressedImageConstPtr& image, int decode_flag); + + +/** + * @brief encodeImage standadlone encoding function wrapping around cv::imencode for compressin sensor_msgs::Image messages + * @param iamge the image message to encode + * @param encode_flag one of compressionFormat::JPEG or compressionFormat::PNG + * @param params Format-specific parameters. See cv::imwrite and cv::ImwriteFlags. + * @return + */ +sensor_msgs::CompressedImagePtr encodeImage(const sensor_msgs::Image &image, compressionFormat encode_flag, std::vector params = std::vector()); + } //namespace compressed_image_transport #endif diff --git a/compressed_image_transport/src/compressed_publisher.cpp b/compressed_image_transport/src/compressed_publisher.cpp index ef01e35..69ace21 100644 --- a/compressed_image_transport/src/compressed_publisher.cpp +++ b/compressed_image_transport/src/compressed_publisher.cpp @@ -78,14 +78,6 @@ void CompressedPublisher::configCb(Config& config, uint32_t level) void CompressedPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const { - // Compressed image message - sensor_msgs::CompressedImage compressed; - compressed.header = message.header; - compressed.format = message.encoding; - - // Compression settings - std::vector params; - // Get codec configuration compressionFormat encodingFormat = UNDEFINED; if (config_.format == compressed_image_transport::CompressedPublisher_jpeg) @@ -93,16 +85,15 @@ void CompressedPublisher::publish(const sensor_msgs::Image& message, const Publi if (config_.format == compressed_image_transport::CompressedPublisher_png) encodingFormat = PNG; - // Bit depth of image encoding - int bitDepth = enc::bitDepth(message.encoding); - int numChannels = enc::numChannels(message.encoding); - + // Compression settings + std::vector params; + sensor_msgs::CompressedImagePtr compressed; switch (encodingFormat) { // JPEG Compression case JPEG: { - params.resize(9, 0); + params.resize(8, 0); params[0] = IMWRITE_JPEG_QUALITY; params[1] = config_.jpeg_quality; params[2] = IMWRITE_JPEG_PROGRESSIVE; @@ -112,122 +103,48 @@ void CompressedPublisher::publish(const sensor_msgs::Image& message, const Publi params[6] = IMWRITE_JPEG_RST_INTERVAL; params[7] = config_.jpeg_restart_interval; - // Update ros message format header - compressed.format += "; jpeg compressed "; - - // Check input format - if ((bitDepth == 8) || (bitDepth == 16)) - { - // Target image format - std::string targetFormat; - if (enc::isColor(message.encoding)) - { - // convert color images to BGR8 format - targetFormat = "bgr8"; - compressed.format += targetFormat; - } - - // OpenCV-ros bridge - try - { - boost::shared_ptr tracked_object; - cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat); - - // Compress image - if (cv::imencode(".jpg", cv_ptr->image, compressed.data, params)) - { - - float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize()) - / (float)compressed.data.size(); - ROS_DEBUG("Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size()); - } - else - { - ROS_ERROR("cv::imencode (jpeg) failed on input image"); - } - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("%s", e.what()); - } - catch (cv::Exception& e) - { - ROS_ERROR("%s", e.what()); - } - - // Publish message - publish_fn(compressed); + // Publish message + try { + compressed = encodeImage(message, encodingFormat, params); + } + catch (cv_bridge::Exception& e) { + ROS_ERROR("%s", e.what()); + } + catch (cv::Exception& e) { + ROS_ERROR("%s", e.what()); + } + catch (std::runtime_error& e) { + ROS_ERROR("%s", e.what()); } - else - ROS_ERROR("Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str()); - break; } - // PNG Compression + + // PNG Compression case PNG: { - params.resize(3, 0); + params.resize(2, 0); params[0] = IMWRITE_PNG_COMPRESSION; params[1] = config_.png_level; - - // Update ros message format header - compressed.format += "; png compressed "; - - // Check input format - if ((bitDepth == 8) || (bitDepth == 16)) - { - - // Target image format - stringstream targetFormat; - if (enc::isColor(message.encoding)) - { - // convert color images to RGB domain - targetFormat << "bgr" << bitDepth; - compressed.format += targetFormat.str(); - } - - // OpenCV-ros bridge - try - { - boost::shared_ptr tracked_object; - cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat.str()); - - // Compress image - if (cv::imencode(".png", cv_ptr->image, compressed.data, params)) - { - - float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize()) - / (float)compressed.data.size(); - ROS_DEBUG("Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size()); - } - else - { - ROS_ERROR("cv::imencode (png) failed on input image"); - } - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("%s", e.what()); - return; - } - catch (cv::Exception& e) - { - ROS_ERROR("%s", e.what()); - return; - } - - // Publish message - publish_fn(compressed); + try { + compressed = encodeImage(message, encodingFormat, params); + } + catch (cv_bridge::Exception& e) { + ROS_ERROR("%s", e.what()); + } + catch (cv::Exception& e) { + ROS_ERROR("%s", e.what()); + } + catch (std::runtime_error& e) { + ROS_ERROR("%s", e.what()); } - else - ROS_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str()); break; } - default: ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str()); break; } + // Publish message + publish_fn(*compressed); } diff --git a/compressed_image_transport/src/compressed_subscriber.cpp b/compressed_image_transport/src/compressed_subscriber.cpp index a84a51f..529e46b 100644 --- a/compressed_image_transport/src/compressed_subscriber.cpp +++ b/compressed_image_transport/src/compressed_subscriber.cpp @@ -84,85 +84,20 @@ void CompressedSubscriber::shutdown() void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message, const Callback& user_cb) - { - - cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage); - - // Copy message header - cv_ptr->header = message->header; - - // Decode color/mono image - try + try { - cv_ptr->image = cv::imdecode(cv::Mat(message->data), imdecode_flag_); - - // Assign image encoding string - const size_t split_pos = message->format.find(';'); - if (split_pos==std::string::npos) - { - // Older version of compressed_image_transport does not signal image format - switch (cv_ptr->image.channels()) - { - case 1: - cv_ptr->encoding = enc::MONO8; - break; - case 3: - cv_ptr->encoding = enc::BGR8; - break; - default: - ROS_ERROR("Unsupported number of channels: %i", cv_ptr->image.channels()); - break; - } - } else - { - std::string image_encoding = message->format.substr(0, split_pos); - - cv_ptr->encoding = image_encoding; - - if ( enc::isColor(image_encoding)) - { - std::string compressed_encoding = message->format.substr(split_pos); - bool compressed_bgr_image = (compressed_encoding.find("compressed bgr") != std::string::npos); - - // Revert color transformation - if (compressed_bgr_image) - { - // if necessary convert colors from bgr to rgb - if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16)) - cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB); - - if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16)) - cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA); - - if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16)) - cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA); - } else - { - // if necessary convert colors from rgb to bgr - if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16)) - cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR); - - if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16)) - cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA); - - if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16)) - cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA); - } - } - } + // Decode color/mono image, and call user callback + user_cb(decodeCompressedImage(message, imdecode_flag_)); } - catch (cv::Exception& e) + catch (cv::Exception& e) + { + ROS_ERROR("%s", e.what()); + } + catch (std::runtime_error& e) { ROS_ERROR("%s", e.what()); } - - size_t rows = cv_ptr->image.rows; - size_t cols = cv_ptr->image.cols; - - if ((rows > 0) && (cols > 0)) - // Publish message to user callback - user_cb(cv_ptr->toImageMsg()); } } //namespace compressed_image_transport diff --git a/compressed_image_transport/src/compression_common.cpp b/compressed_image_transport/src/compression_common.cpp new file mode 100644 index 0000000..a2bcf4a --- /dev/null +++ b/compressed_image_transport/src/compression_common.cpp @@ -0,0 +1,203 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 20012, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#include +#include +#include +#include +#include +#include + +namespace enc = sensor_msgs::image_encodings; + +namespace compressed_image_transport { + sensor_msgs::ImagePtr decodeCompressedImage(const sensor_msgs::CompressedImageConstPtr &image, int decode_flag) { + if (!image) + throw std::runtime_error("Call to decode a compressed image received a NULL pointer."); + + cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage); + + // Copy message header + cv_ptr->header = image->header; + + // Decode color/mono image + cv_ptr->image = cv::imdecode(cv::Mat(image->data), decode_flag); + + // Assign image encoding string + const size_t split_pos = image->format.find(';'); + if (split_pos == std::string::npos) { + // Older version of compressed_image_transport does not signal image format + switch (cv_ptr->image.channels()) { + case 1: + cv_ptr->encoding = enc::MONO8; + break; + case 3: + cv_ptr->encoding = enc::BGR8; + break; + default: { + std::stringstream ss; + ss << "Unsupported number of channels: " << cv_ptr->image.channels(); + throw std::runtime_error(ss.str()); + } + } + } else { + std::string image_encoding = image->format.substr(0, split_pos); + + cv_ptr->encoding = image_encoding; + + if (enc::isColor(image_encoding)) { + std::string compressed_encoding = image->format.substr(split_pos); + bool compressed_bgr_image = (compressed_encoding.find("compressed bgr") != std::string::npos); + + // Revert color transformation + if (compressed_bgr_image) { + // if necessary convert colors from bgr to rgb + if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16)) + cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB); + + if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16)) + cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA); + + if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16)) + cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA); + } else { + // if necessary convert colors from rgb to bgr + if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16)) + cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR); + + if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16)) + cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA); + + if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16)) + cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA); + } + } + } + + if ((cv_ptr->image.rows > 0) && (cv_ptr->image.cols > 0)) + return cv_ptr->toImageMsg(); + else { + std::stringstream ss; + ss << "Could not extract meaningful image. One of the dimensions was 0. Rows: " + << cv_ptr->image.rows << ", columns: " << cv_ptr->image.cols << "."; + throw std::runtime_error(ss.str()); + } + } + + sensor_msgs::CompressedImagePtr encodeImage(const sensor_msgs::Image &message, compressionFormat encode_flag, std::vector params) { + + boost::shared_ptr compressed(new sensor_msgs::CompressedImage); + compressed->header = message.header; + compressed->format = message.encoding; + // Bit depth of image encoding + int bitDepth = enc::bitDepth(message.encoding); + int numChannels = enc::numChannels(message.encoding); + + switch (encode_flag) { + case JPEG: + { + compressed->format += "; jpeg compressed "; + // Check input format + if ((bitDepth == 8) || (bitDepth == 16)) { + // Target image format + std::string targetFormat; + if (enc::isColor(message.encoding)) { + // convert color images to BGR8 format + targetFormat = "bgr8"; + compressed->format += targetFormat; + } + + // OpenCV-ros bridge + boost::shared_ptr tracked_object; + cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat); + + // Compress image + if (cv::imencode(".jpg", cv_ptr->image, compressed->data, params)) { + + float cRatio = (float) (cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize()) + / (float) compressed->data.size(); + ROS_DEBUG("Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, + compressed->data.size()); + } else { + throw std::runtime_error("cv::imencode (jpeg) failed on input image"); + } + return compressed; + } else { + throw std::runtime_error("Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: "+ message.encoding + + ")"); + } + } + case PNG: + { + // Update ros message format header + compressed->format += "; png compressed "; + // Check input format + if ((bitDepth == 8) || (bitDepth == 16)) { + + // Target image format + std::ostringstream targetFormat; + if (enc::isColor(message.encoding)) { + // convert color images to RGB domain + targetFormat << "bgr" << bitDepth; + compressed->format += targetFormat.str(); + } + + boost::shared_ptr tracked_object; + cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat.str()); + + // Compress image + if (cv::imencode(".png", cv_ptr->image, compressed->data, params)) { + + float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())/ (float)compressed->data.size(); + ROS_DEBUG("Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed->data.size()); + } else { + throw std::runtime_error("cv::imencode (png) failed on input image"); + } + // Publish message + return compressed; + } else { + throw std::runtime_error("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: "+ message.encoding +")"); + break; + } + } + default: + { + throw std::runtime_error("Unknown compression type, valid options are 'jpeg(0)' and 'png(1)'"); + break; + } + } + return compressed; + } + +}