$search
00001 #include "compressed_imagem_transport/compressed_publisher.h" 00002 #include <sensor_msgs/image_encodings.h> 00003 #include <cv_bridge/cv_bridge.h> 00004 #include <cv.h> 00005 #include <highgui.h> 00006 #include <boost/make_shared.hpp> 00007 00008 #include "compressed_image_transport/compression_common.h" 00009 00010 #include <vector> 00011 #include <sstream> 00012 00013 using namespace cv; 00014 using namespace std; 00015 00016 namespace enc = sensor_msgs::image_encodings; 00017 namespace cit = compressed_image_transport; 00018 00019 namespace compressed_imagem_transport { 00020 00021 00022 void CompressedPublisher::configCb(Config& config, uint32_t level) 00023 { 00024 config_ = config; 00025 } 00026 00027 00028 00029 void CompressedPublisher::publish(const sensor_msgs::Image& message, 00030 const message_transport::SimplePublisherPlugin<sensor_msgs::Image,sensor_msgs::CompressedImage>::PublishFn& publish_fn) const 00031 { 00032 // Compressed image message 00033 sensor_msgs::CompressedImage compressed; 00034 compressed.header = message.header; 00035 compressed.format = message.encoding; 00036 00037 // Compression settings 00038 std::vector<int> params; 00039 params.resize(3, 0); 00040 00041 // Get codec configuration 00042 cit::compressionFormat encodingFormat = cit::UNDEFINED; 00043 if (config_.format == "jpeg") 00044 encodingFormat = cit::JPEG; 00045 if (config_.format == "png") 00046 encodingFormat = cit::PNG; 00047 00048 // Bit depth of image encoding 00049 int bitDepth = enc::bitDepth(message.encoding); 00050 int numChannels = enc::numChannels(message.encoding); 00051 00052 switch (encodingFormat) 00053 { 00054 // JPEG Compression 00055 case cit::JPEG: 00056 { 00057 params[0] = CV_IMWRITE_JPEG_QUALITY; 00058 params[1] = config_.jpeg_quality; 00059 00060 // Update ros message format header 00061 compressed.format += "; jpeg compressed"; 00062 00063 // Check input format 00064 if ((bitDepth == 8) && // JPEG only works on 8bit images 00065 ((numChannels == 1) || (numChannels == 3))) 00066 { 00067 00068 // Target image format 00069 stringstream targetFormat; 00070 if (enc::isColor(message.encoding)) 00071 { 00072 // convert color images to RGB domain 00073 targetFormat << "rgb" << bitDepth; 00074 } 00075 00076 // OpenCV-ros bridge 00077 cv_bridge::CvImagePtr cv_ptr; 00078 try 00079 { 00080 cv_ptr = cv_bridge::toCvCopy(message, targetFormat.str()); 00081 00082 // Compress image 00083 if (cv::imencode(".jpg", cv_ptr->image, compressed.data, params)) 00084 { 00085 00086 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize()) 00087 / (float)compressed.data.size(); 00088 ROS_DEBUG("Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, (long unsigned int)compressed.data.size()); 00089 } 00090 else 00091 { 00092 ROS_ERROR("cv::imencode (jpeg) failed on input image"); 00093 } 00094 } 00095 catch (cv_bridge::Exception& e) 00096 { 00097 ROS_ERROR("%s", e.what()); 00098 } 00099 catch (cv::Exception& e) 00100 { 00101 ROS_ERROR("%s", e.what()); 00102 } 00103 00104 // Publish message 00105 publish_fn(compressed); 00106 } 00107 else 00108 ROS_ERROR("Compressed Image Transport - JPEG compression requires 8-bit, 1/3-channel images (input format is: %s)", message.encoding.c_str()); 00109 00110 break; 00111 } 00112 // PNG Compression 00113 case cit::PNG: 00114 { 00115 params[0] = CV_IMWRITE_PNG_COMPRESSION; 00116 params[1] = config_.png_level; 00117 00118 // Update ros message format header 00119 compressed.format += "; png compressed"; 00120 00121 // Check input format 00122 if (((bitDepth == 16) || (bitDepth == 8)) && ((numChannels == 1) || (numChannels == 3))) 00123 { 00124 00125 // Target image format 00126 stringstream targetFormat; 00127 if (enc::isColor(message.encoding)) 00128 { 00129 // convert color images to RGB domain 00130 targetFormat << "rgb" << bitDepth; 00131 } 00132 00133 // OpenCV-ros bridge 00134 cv_bridge::CvImagePtr cv_ptr; 00135 try 00136 { 00137 cv_ptr = cv_bridge::toCvCopy(message, targetFormat.str()); 00138 00139 // Compress image 00140 if (cv::imencode(".png", cv_ptr->image, compressed.data, params)) 00141 { 00142 00143 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize()) 00144 / (float)compressed.data.size(); 00145 ROS_DEBUG("Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, (long unsigned int)compressed.data.size()); 00146 } 00147 else 00148 { 00149 ROS_ERROR("cv::imencode (png) failed on input image"); 00150 } 00151 } 00152 catch (cv_bridge::Exception& e) 00153 { 00154 ROS_ERROR("%s", e.what()); 00155 } 00156 catch (cv::Exception& e) 00157 { 00158 ROS_ERROR("%s", e.what()); 00159 } 00160 00161 // Publish message 00162 publish_fn(compressed); 00163 } 00164 else 00165 ROS_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit, 1/3-channel images (input format is: %s)", message.encoding.c_str()); 00166 break; 00167 } 00168 00169 default: 00170 ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str()); 00171 break; 00172 } 00173 00174 } 00175 00176 } //namespace compressed_imagem_transport