compressed_subscriber.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_subscriber.h"
00036 #include <sensor_msgs/image_encodings.h>
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <opencv2/highgui/highgui.hpp>
00039 #include <opencv2/imgproc/imgproc.hpp>
00040 
00041 #include "compressed_image_transport/compression_common.h"
00042 
00043 #include <limits>
00044 #include <vector>
00045 
00046 using namespace cv;
00047 
00048 namespace enc = sensor_msgs::image_encodings;
00049 
00050 namespace compressed_image_transport
00051 {
00052 
00053 void CompressedSubscriber::subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00054                              const Callback& callback, const ros::VoidPtr& tracked_object,
00055                              const image_transport::TransportHints& transport_hints)
00056 {
00057     typedef image_transport::SimpleSubscriberPlugin<sensor_msgs::CompressedImage> Base;
00058     Base::subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00059 
00060     // Set up reconfigure server for this topic
00061     reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00062     ReconfigureServer::CallbackType f = boost::bind(&CompressedSubscriber::configCb, this, _1, _2);
00063     reconfigure_server_->setCallback(f);
00064 }
00065 
00066 
00067 void CompressedSubscriber::configCb(Config& config, uint32_t level)
00068 {
00069   config_ = config;
00070   if (config_.mode == compressed_image_transport::CompressedSubscriber_gray) {
00071       imdecode_flag_ = cv::IMREAD_GRAYSCALE;
00072   } else if (config_.mode == compressed_image_transport::CompressedSubscriber_color) {
00073       imdecode_flag_ = cv::IMREAD_COLOR;
00074   } else /*if (config_.mode == compressed_image_transport::CompressedSubscriber_unchanged)*/ {
00075       imdecode_flag_ = cv::IMREAD_UNCHANGED;
00076   } 
00077 }
00078 
00079 
00080 void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
00081                                             const Callback& user_cb)
00082 
00083 {
00084 
00085   cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00086 
00087   // Copy message header
00088   cv_ptr->header = message->header;
00089 
00090   // Decode color/mono image
00091   try
00092   {
00093     cv_ptr->image = cv::imdecode(cv::Mat(message->data), imdecode_flag_);
00094 
00095     // Assign image encoding string
00096     const size_t split_pos = message->format.find(';');
00097     if (split_pos==std::string::npos)
00098     {
00099       // Older version of compressed_image_transport does not signal image format
00100       switch (cv_ptr->image.channels())
00101       {
00102         case 1:
00103           cv_ptr->encoding = enc::MONO8;
00104           break;
00105         case 3:
00106           cv_ptr->encoding = enc::BGR8;
00107           break;
00108         default:
00109           ROS_ERROR("Unsupported number of channels: %i", cv_ptr->image.channels());
00110           break;
00111       }
00112     } else
00113     {
00114       std::string image_encoding = message->format.substr(0, split_pos);
00115 
00116       cv_ptr->encoding = image_encoding;
00117 
00118       if ( enc::isColor(image_encoding))
00119       {
00120         std::string compressed_encoding = message->format.substr(split_pos);
00121         bool compressed_bgr_image = (compressed_encoding.find("compressed bgr") != std::string::npos);
00122 
00123         // Revert color transformation
00124         if (compressed_bgr_image)
00125         {
00126           // if necessary convert colors from bgr to rgb
00127           if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16))
00128             cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB);
00129 
00130           if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
00131             cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA);
00132 
00133           if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
00134             cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA);
00135         } else
00136         {
00137           // if necessary convert colors from rgb to bgr
00138           if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16))
00139             cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR);
00140 
00141           if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
00142             cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA);
00143 
00144           if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
00145             cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
00146         }
00147       }
00148     }
00149   }
00150   catch (cv::Exception& e)
00151   {
00152     ROS_ERROR("%s", e.what());
00153   }
00154 
00155   size_t rows = cv_ptr->image.rows;
00156   size_t cols = cv_ptr->image.cols;
00157 
00158   if ((rows > 0) && (cols > 0))
00159     // Publish message to user callback
00160     user_cb(cv_ptr->toImageMsg());
00161 }
00162 
00163 } //namespace compressed_image_transport


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl
autogenerated on Tue Oct 4 2016 03:52:08