convex_hull_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2014, Kei Okada.
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 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/ShapeDescriptors/hull_demo.cpp
00042 #include <ros/ros.h>
00043 #include "opencv_apps/nodelet.h"
00044 #include <image_transport/image_transport.h>
00045 #include <sensor_msgs/image_encodings.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <sensor_msgs/image_encodings.h>
00048 
00049 #include <opencv2/highgui/highgui.hpp>
00050 #include <opencv2/imgproc/imgproc.hpp>
00051 
00052 #include <dynamic_reconfigure/server.h>
00053 #include "opencv_apps/ConvexHullConfig.h"
00054 #include "opencv_apps/Contour.h"
00055 #include "opencv_apps/ContourArray.h"
00056 #include "opencv_apps/ContourArrayStamped.h"
00057 
00058 namespace convex_hull {
00059 class ConvexHullNodelet : public opencv_apps::Nodelet
00060 {
00061   image_transport::Publisher img_pub_;
00062   image_transport::Subscriber img_sub_;
00063   image_transport::CameraSubscriber cam_sub_;
00064   ros::Publisher msg_pub_;
00065 
00066   boost::shared_ptr<image_transport::ImageTransport> it_;
00067 
00068   typedef convex_hull::ConvexHullConfig Config;
00069   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00070   Config config_;
00071   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00072 
00073   bool debug_view_;
00074   ros::Time prev_stamp_;
00075 
00076   int threshold_;
00077 
00078   std::string window_name_;
00079   static bool need_config_update_;
00080 
00081   void reconfigureCallback(Config &new_config, uint32_t level)
00082   {
00083     config_ = new_config;
00084     threshold_ = config_.threshold;
00085   }
00086 
00087   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00088   {
00089     if (frame.empty())
00090       return image_frame;
00091     return frame;
00092   }
00093 
00094   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00095   {
00096     do_work(msg, cam_info->header.frame_id);
00097   }
00098 
00099   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00100   {
00101     do_work(msg, msg->header.frame_id);
00102   }
00103 
00104   static void trackbarCallback( int, void* )
00105   {
00106     need_config_update_ = true;
00107   }
00108 
00109   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00110   {
00111     // Work on the image.
00112     try
00113     {
00114       // Convert the image into something opencv can handle.
00115       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00116 
00117       // Messages
00118       opencv_apps::ContourArrayStamped contours_msg;
00119       contours_msg.header = msg->header;
00120 
00121       // Do the work
00122       cv::Mat src_gray;
00123 
00125       if ( frame.channels() > 1 ) {
00126         cv::cvtColor( frame, src_gray, cv::COLOR_RGB2GRAY );
00127       } else {
00128         src_gray = frame;
00129       }
00130       cv::blur( src_gray, src_gray, cv::Size(3,3) );
00131 
00133       if( debug_view_) {
00134         cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00135       }
00136 
00137       cv::Mat threshold_output;
00138       int max_thresh = 255;
00139       std::vector<std::vector<cv::Point> > contours;
00140       std::vector<cv::Vec4i> hierarchy;
00141       cv::RNG rng(12345);
00142 
00144       cv::threshold( src_gray, threshold_output, threshold_, 255, cv::THRESH_BINARY );
00145 
00147       cv::findContours( threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0) );
00148 
00150       std::vector<std::vector<cv::Point> >hull( contours.size() );
00151       for( size_t i = 0; i < contours.size(); i++ )
00152       {   cv::convexHull( cv::Mat(contours[i]), hull[i], false ); }
00153 
00155       cv::Mat drawing = cv::Mat::zeros( threshold_output.size(), CV_8UC3 );
00156       for( size_t i = 0; i< contours.size(); i++ )
00157       {
00158         cv::Scalar color = cv::Scalar( rng.uniform(0, 255), rng.uniform(0,255), rng.uniform(0,255) );
00159         cv::drawContours( drawing, contours, (int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point() );
00160         cv::drawContours( drawing, hull, (int)i, color, 4, 8, std::vector<cv::Vec4i>(), 0, cv::Point() );
00161 
00162         opencv_apps::Contour contour_msg;
00163         for ( size_t j = 0; j < hull[i].size(); j++ ) {
00164           opencv_apps::Point2D point_msg;
00165           point_msg.x = hull[i][j].x;
00166           point_msg.y = hull[i][j].y;
00167           contour_msg.points.push_back(point_msg);
00168         }
00169         contours_msg.contours.push_back(contour_msg);
00170       }
00171 
00173       if( debug_view_) {
00174         if (need_config_update_) {
00175           config_.threshold = threshold_;
00176           reconfigure_server_->updateConfig(config_);
00177           need_config_update_ = false;
00178         }
00179         cv::createTrackbar( "Threshold:", window_name_, &threshold_, max_thresh, trackbarCallback);
00180 
00181         cv::imshow( window_name_, drawing );
00182         int c = cv::waitKey(1);
00183       }
00184 
00185       // Publish the image.
00186       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, drawing).toImageMsg();
00187       img_pub_.publish(out_img);
00188       msg_pub_.publish(contours_msg);
00189     }
00190     catch (cv::Exception &e)
00191     {
00192       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00193     }
00194 
00195     prev_stamp_ = msg->header.stamp;
00196   }
00197 
00198   void subscribe()
00199   {
00200     NODELET_DEBUG("Subscribing to image topic.");
00201     if (config_.use_camera_info)
00202       cam_sub_ = it_->subscribeCamera("image", 3, &ConvexHullNodelet::imageCallbackWithInfo, this);
00203     else
00204       img_sub_ = it_->subscribe("image", 3, &ConvexHullNodelet::imageCallback, this);
00205   }
00206 
00207   void unsubscribe()
00208   {
00209     NODELET_DEBUG("Unsubscribing from image topic.");
00210     img_sub_.shutdown();
00211     cam_sub_.shutdown();
00212   }
00213 
00214 
00215 public:
00216   virtual void onInit()
00217   {
00218     Nodelet::onInit();
00219     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00220 
00221     pnh_->param("debug_view", debug_view_, false);
00222     if (debug_view_) {
00223       always_subscribe_ = true;
00224     }
00225     prev_stamp_ = ros::Time(0, 0);
00226 
00227     window_name_ = "Hull Demo";
00228     threshold_ = 100;
00229     
00230     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00231     dynamic_reconfigure::Server<Config>::CallbackType f =
00232       boost::bind(&ConvexHullNodelet::reconfigureCallback, this, _1, _2);
00233     reconfigure_server_->setCallback(f);
00234 
00235     img_pub_ = advertiseImage(*pnh_, "image", 1);
00236     msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "hulls", 1);
00237     onInitPostProcess();
00238   }
00239 };
00240 bool ConvexHullNodelet::need_config_update_ = false;
00241 }
00242 
00243 #include <pluginlib/class_list_macros.h>
00244 PLUGINLIB_EXPORT_CLASS(convex_hull::ConvexHullNodelet, nodelet::Nodelet);


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