simple_compressed_example_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2015, Tal Regev.
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 Kei Okada 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 //http://wiki.ros.org/cv_bridge/Tutorials/UsingCvBridgeToConvertBetweenROSImagesAndOpenCVImages
00040 #include <ros/ros.h>
00041 #include <sensor_msgs/CompressedImage.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <nodelet/nodelet.h>
00044 #include <image_transport/image_transport.h>
00045 #include <cv_bridge/cv_bridge.h>
00046 #include <sensor_msgs/image_encodings.h>
00047 
00048 #include <opencv2/highgui/highgui.hpp>
00049 #include <opencv2/imgproc/imgproc.hpp>
00050 
00051 
00052 #include <dynamic_reconfigure/server.h>
00053 
00054 
00055 namespace simple_compressed_example {
00056 
00057 static const std::string OPENCV_WINDOW = "Image window";
00058 
00059 class ImageConverter
00060 {
00061   ros::NodeHandle nh_;
00062   ros::Subscriber image_sub_;
00063   ros::Publisher image_pub_;
00064   bool debug_view_;
00065 
00066 public:
00067   ImageConverter()
00068   {
00069       // Subscrive to input video feed and publish output video feed
00070     image_sub_ = nh_.subscribe("image/compressed", 1,
00071             &ImageConverter::imageCb,this);
00072     image_pub_ = nh_.advertise<sensor_msgs::CompressedImage>("/image_converter/output_video/compressed", 1);
00073 
00074     ros::NodeHandle pnh_("~");
00075     pnh_.param("debug_view", debug_view_, false);
00076     if( debug_view_) {
00077       cv::namedWindow(OPENCV_WINDOW);
00078     }
00079   }
00080 
00081   ~ImageConverter()
00082   {
00083     if( debug_view_) {
00084       cv::destroyWindow(OPENCV_WINDOW);
00085     }
00086   }
00087 
00088   void imageCb(const sensor_msgs::CompressedImageConstPtr& msg)
00089   {
00090     cv_bridge::CvImagePtr cv_ptr;
00091     try
00092     {
00093       /*
00094         Supporting CompressedImage in cv_bridge has been started from 1.11.9 (2015-11-29)
00095         note : hydro 1.10.18, indigo : 1.11.13 ...
00096         https://github.com/ros-perception/vision_opencv/pull/70
00097        */
00098 #ifndef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
00099       cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00100 #else
00101       //cv_ptr = cv_bridge::toCvCopyImpl(matFromImage(msg), msg.header, sensor_msgs::image_encodings::BGR8, sensor_msgs::image_encodings::BGR8);
00102           //cv::Mat matFromImage(const sensor_msgs::CompressedImage& source)
00103           cv::Mat jpegData(1,msg->data.size(),CV_8UC1);
00104           jpegData.data     = const_cast<uchar*>(&msg->data[0]);
00105           cv::InputArray data(jpegData);
00106           cv::Mat image     = cv::imdecode(data,cv::IMREAD_COLOR);
00107 
00108         //cv_ptr = cv_bridge::toCvCopyImpl(bgrMat, msg->header, sensor_msgs::image_encodings::BGR8, sensor_msgs::image_encodings::BGR8);
00109         sensor_msgs::Image ros_image;
00110         ros_image.header = msg->header;
00111         ros_image.height = image.rows;
00112         ros_image.width = image.cols;
00113         ros_image.encoding = sensor_msgs::image_encodings::BGR8;
00114         ros_image.is_bigendian = false;
00115         ros_image.step = image.cols * image.elemSize();
00116         size_t size = ros_image.step * image.rows;
00117         ros_image.data.resize(size);
00118 
00119         if (image.isContinuous())
00120           {
00121             memcpy((char*)(&ros_image.data[0]), image.data, size);
00122           }
00123         else
00124           {
00125             // Copy by row by row
00126             uchar* ros_data_ptr = (uchar*)(&ros_image.data[0]);
00127             uchar* cv_data_ptr = image.data;
00128             for (int i = 0; i < image.rows; ++i)
00129               {
00130                 memcpy(ros_data_ptr, cv_data_ptr, ros_image.step);
00131                 ros_data_ptr += ros_image.step;
00132                 cv_data_ptr += image.step;
00133               }
00134           }
00135         cv_ptr = cv_bridge::toCvCopy(ros_image, sensor_msgs::image_encodings::BGR8);
00136 #endif
00137     }
00138     catch (cv_bridge::Exception& e)
00139     {
00140       ROS_ERROR("cv_bridge exception: %s", e.what());
00141       return;
00142     }
00143 
00144     // Draw an example circle on the video stream
00145     if (cv_ptr->image.rows > 110 && cv_ptr->image.cols > 110)
00146       cv::circle(cv_ptr->image, cv::Point(cv_ptr->image.cols/2, cv_ptr->image.rows/2), 100, CV_RGB(255,0,0));
00147 
00148     if( debug_view_) {
00149       // Update GUI Window
00150       cv::imshow(OPENCV_WINDOW, cv_ptr->image);
00151       cv::waitKey(3);
00152     }
00153 
00154     // Output modified video stream
00155 #ifndef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
00156     image_pub_.publish(cv_ptr->toCompressedImageMsg());
00157 #else
00158     image_pub_.publish(toCompressedImageMsg(cv_ptr));
00159 #endif
00160   }
00161 #ifdef CV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED
00162   sensor_msgs::CompressedImage toCompressedImageMsg(cv_bridge::CvImagePtr cv_ptr) const
00163   {
00164     sensor_msgs::CompressedImage ros_image;
00165     const std::string dst_format = std::string();
00166     ros_image.header = cv_ptr->header;
00167     cv::Mat image;
00168     if(cv_ptr->encoding != sensor_msgs::image_encodings::BGR8)
00169       {
00170         cv_bridge::CvImagePtr tempThis = boost::make_shared<cv_bridge::CvImage>(*cv_ptr);
00171         cv_bridge::CvImagePtr temp = cv_bridge::cvtColor(tempThis,sensor_msgs::image_encodings::BGR8);
00172         cv_ptr->image = temp->image;
00173       }
00174     else
00175       {
00176         image = cv_ptr->image;
00177       }
00178     std::vector<uchar> buf;
00179     if (dst_format.empty() || dst_format == "jpg")
00180       {
00181         ros_image.format = "jpg";
00182         cv::imencode(".jpg", image, buf);
00183       }
00184 
00185     if (dst_format == "png")
00186       {
00187         ros_image.format = "png";
00188         cv::imencode(".png", image, buf);
00189       }
00190 
00191     //TODO: check this formats (on rviz) and add more formats
00192     //from http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags)
00193     if (dst_format == "jp2")
00194       {
00195         ros_image.format = "jp2";
00196         cv::imencode(".jp2", image, buf);
00197       }
00198 
00199     if (dst_format == "bmp")
00200       {
00201         ros_image.format = "bmp";
00202         cv::imencode(".bmp", image, buf);
00203       }
00204 
00205     if (dst_format == "tif")
00206       {
00207         ros_image.format = "tif";
00208         cv::imencode(".tif", image, buf);
00209       }
00210 
00211     ros_image.data = buf;
00212     return ros_image;
00213   }
00214 #endif
00215 };
00216 
00217 
00218 class SimpleCompressedExampleNodelet : public nodelet::Nodelet
00219 {
00220 
00221 
00222 public:
00223   virtual void onInit()
00224   {
00225       simple_compressed_example::ImageConverter ic;
00226       ros::spin();
00227   }
00228 };
00229 
00230 }
00231 
00232 #include <pluginlib/class_list_macros.h>
00233 PLUGINLIB_EXPORT_CLASS(simple_compressed_example::SimpleCompressedExampleNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:59