compressed_publisher.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 20012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include "compressed_image_transport/compressed_publisher.h"
00036 #include <cv_bridge/cv_bridge.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <opencv2/highgui/highgui.hpp>
00039 #include <opencv2/imgcodecs.hpp>
00040 #include <boost/make_shared.hpp>
00041 
00042 #include "compressed_image_transport/compression_common.h"
00043 
00044 #include <vector>
00045 #include <sstream>
00046 
00047 // If OpenCV4
00048 #if CV_VERSION_MAJOR > 3
00049 #include <opencv2/imgcodecs/legacy/constants_c.h>
00050 #endif
00051 
00052 using namespace cv;
00053 using namespace std;
00054 
00055 namespace enc = sensor_msgs::image_encodings;
00056 
00057 namespace compressed_image_transport
00058 {
00059 
00060 void CompressedPublisher::advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00061                                         const image_transport::SubscriberStatusCallback &user_connect_cb,
00062                                         const image_transport::SubscriberStatusCallback &user_disconnect_cb,
00063                                         const ros::VoidPtr &tracked_object, bool latch)
00064 {
00065   typedef image_transport::SimplePublisherPlugin<sensor_msgs::CompressedImage> Base;
00066   Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
00067 
00068   // Set up reconfigure server for this topic
00069   reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00070   ReconfigureServer::CallbackType f = boost::bind(&CompressedPublisher::configCb, this, _1, _2);
00071   reconfigure_server_->setCallback(f);
00072 }
00073 
00074 void CompressedPublisher::configCb(Config& config, uint32_t level)
00075 {
00076   config_ = config;
00077 }
00078 
00079 void CompressedPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
00080 {
00081   // Compressed image message
00082   sensor_msgs::CompressedImage compressed;
00083   compressed.header = message.header;
00084   compressed.format = message.encoding;
00085 
00086   // Compression settings
00087   std::vector<int> params;
00088 
00089   // Get codec configuration
00090   compressionFormat encodingFormat = UNDEFINED;
00091   if (config_.format == compressed_image_transport::CompressedPublisher_jpeg)
00092     encodingFormat = JPEG;
00093   if (config_.format == compressed_image_transport::CompressedPublisher_png)
00094     encodingFormat = PNG;
00095 
00096   // Bit depth of image encoding
00097   int bitDepth = enc::bitDepth(message.encoding);
00098   int numChannels = enc::numChannels(message.encoding);
00099 
00100   switch (encodingFormat)
00101   {
00102     // JPEG Compression
00103     case JPEG:
00104     {
00105       params.resize(9, 0);
00106       params[0] = IMWRITE_JPEG_QUALITY;
00107       params[1] = config_.jpeg_quality;
00108       params[2] = IMWRITE_JPEG_PROGRESSIVE;
00109       params[3] = config_.jpeg_progressive ? 1 : 0;
00110       params[4] = IMWRITE_JPEG_OPTIMIZE;
00111       params[5] = config_.jpeg_optimize ? 1 : 0;
00112       params[6] = IMWRITE_JPEG_RST_INTERVAL;
00113       params[7] = config_.jpeg_restart_interval;
00114 
00115       // Update ros message format header
00116       compressed.format += "; jpeg compressed ";
00117 
00118       // Check input format
00119       if ((bitDepth == 8) || (bitDepth == 16))
00120       {
00121         // Target image format
00122         std::string targetFormat;
00123         if (enc::isColor(message.encoding))
00124         {
00125           // convert color images to BGR8 format
00126           targetFormat = "bgr8";
00127           compressed.format += targetFormat;
00128         }
00129 
00130         // OpenCV-ros bridge
00131         try
00132         {
00133           boost::shared_ptr<CompressedPublisher> tracked_object;
00134           cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat);
00135 
00136           // Compress image
00137           if (cv::imencode(".jpg", cv_ptr->image, compressed.data, params))
00138           {
00139 
00140             float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00141                 / (float)compressed.data.size();
00142             ROS_DEBUG("Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
00143           }
00144           else
00145           {
00146             ROS_ERROR("cv::imencode (jpeg) failed on input image");
00147           }
00148         }
00149         catch (cv_bridge::Exception& e)
00150         {
00151           ROS_ERROR("%s", e.what());
00152         }
00153         catch (cv::Exception& e)
00154         {
00155           ROS_ERROR("%s", e.what());
00156         }
00157 
00158         // Publish message
00159         publish_fn(compressed);
00160       }
00161       else
00162         ROS_ERROR("Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
00163 
00164       break;
00165     }
00166       // PNG Compression
00167     case PNG:
00168     {
00169       params.resize(3, 0);
00170       params[0] = IMWRITE_PNG_COMPRESSION;
00171       params[1] = config_.png_level;
00172 
00173       // Update ros message format header
00174       compressed.format += "; png compressed ";
00175 
00176       // Check input format
00177       if ((bitDepth == 8) || (bitDepth == 16))
00178       {
00179 
00180         // Target image format
00181         stringstream targetFormat;
00182         if (enc::isColor(message.encoding))
00183         {
00184           // convert color images to RGB domain
00185           targetFormat << "bgr" << bitDepth;
00186           compressed.format += targetFormat.str();
00187         }
00188 
00189         // OpenCV-ros bridge
00190         try
00191         {
00192           boost::shared_ptr<CompressedPublisher> tracked_object;
00193           cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat.str());
00194 
00195           // Compress image
00196           if (cv::imencode(".png", cv_ptr->image, compressed.data, params))
00197           {
00198 
00199             float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00200                 / (float)compressed.data.size();
00201             ROS_DEBUG("Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
00202           }
00203           else
00204           {
00205             ROS_ERROR("cv::imencode (png) failed on input image");
00206           }
00207         }
00208         catch (cv_bridge::Exception& e)
00209         {
00210           ROS_ERROR("%s", e.what());
00211           return;
00212         }
00213         catch (cv::Exception& e)
00214         {
00215           ROS_ERROR("%s", e.what());
00216           return;
00217         }
00218 
00219         // Publish message
00220         publish_fn(compressed);
00221       }
00222       else
00223         ROS_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
00224       break;
00225     }
00226 
00227     default:
00228       ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str());
00229       break;
00230   }
00231 
00232 }
00233 
00234 } //namespace compressed_image_transport


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl
autogenerated on Tue Jul 2 2019 19:53:24