edge_detection_nodelet.cpp
Go to the documentation of this file.
00001 // -*- coding:utf-8-unix; mode: c++; indent-tabs-mode: nil; c-basic-offset: 2; -*-
00002 /*********************************************************************
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2014, Kei Okada.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Kei Okada nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/ImgTrans/
00053 #include <ros/ros.h>
00054 #include "opencv_apps/nodelet.h"
00055 #include <image_transport/image_transport.h>
00056 #include <sensor_msgs/image_encodings.h>
00057 #include <cv_bridge/cv_bridge.h>
00058 
00059 #include <opencv2/highgui/highgui.hpp>
00060 #include <opencv2/imgproc/imgproc.hpp>
00061 
00062 #include <dynamic_reconfigure/server.h>
00063 #include "opencv_apps/EdgeDetectionConfig.h"
00064 
00065 namespace edge_detection {
00066 class EdgeDetectionNodelet : public opencv_apps::Nodelet
00067 {
00068   image_transport::Publisher img_pub_;
00069   image_transport::Subscriber img_sub_;
00070   image_transport::CameraSubscriber cam_sub_;
00071   ros::Publisher msg_pub_;
00072 
00073   boost::shared_ptr<image_transport::ImageTransport> it_;
00074 
00075   typedef edge_detection::EdgeDetectionConfig Config;
00076   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00077   Config config_;
00078   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00079 
00080   bool debug_view_;
00081   ros::Time prev_stamp_;
00082 
00083   int canny_threshold1_;
00084   int canny_threshold2_;
00085   int apertureSize_;
00086   bool L2gradient_;
00087   bool apply_blur_pre_;
00088   bool apply_blur_post_;
00089   int  postBlurSize_;
00090   double  postBlurSigma_;
00091 
00092   std::string window_name_;
00093   static bool need_config_update_;
00094 
00095   void reconfigureCallback(Config &new_config, uint32_t level)
00096   {
00097     config_ = new_config;
00098     canny_threshold1_ = config_.canny_threshold1;
00099     canny_threshold2_ = config_.canny_threshold2;
00100     apertureSize_ = 2*((config_.apertureSize/2)) + 1;
00101     L2gradient_ = config_.L2gradient;
00102 
00103     apply_blur_pre_  = config_.apply_blur_pre;
00104     apply_blur_post_ = config_.apply_blur_post;
00105     postBlurSize_    = 2*((config_.postBlurSize)/2) + 1;
00106     postBlurSigma_   = config_.postBlurSigma;
00107   }
00108 
00109   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00110   {
00111     if (frame.empty())
00112       return image_frame;
00113     return frame;
00114   }
00115 
00116   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00117   {
00118     do_work(msg, cam_info->header.frame_id);
00119   }
00120 
00121   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00122   {
00123     do_work(msg, msg->header.frame_id);
00124   }
00125 
00126   static void trackbarCallback( int, void* )
00127   {
00128     need_config_update_ = true;
00129   }
00130 
00131   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00132   {
00133     // Work on the image.
00134     try
00135     {
00136       // Convert the image into something opencv can handle.
00137       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00138 
00139       // Do the work
00140       cv::Mat src_gray;
00141       cv::GaussianBlur( frame, frame, cv::Size(3,3), 0, 0, cv::BORDER_DEFAULT );
00142 
00144       if ( frame.channels() > 1 ) {
00145         cv::cvtColor( frame, src_gray, cv::COLOR_RGB2GRAY );
00146       } else {
00147         src_gray = frame;
00148       }
00149 
00151       if( debug_view_) {
00152         cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00153       }
00154 
00155       std::string new_window_name;
00156       cv::Mat grad;
00157       switch (config_.edge_type) {
00158         case edge_detection::EdgeDetection_Sobel:
00159           {
00161             cv::Mat grad_x, grad_y;
00162             cv::Mat abs_grad_x, abs_grad_y;
00163 
00164             int scale = 1;
00165             int delta = 0;
00166             int ddepth = CV_16S;
00167 
00169             //Scharr( src_gray, grad_x, ddepth, 1, 0, scale, delta, BORDER_DEFAULT );
00170             cv::Sobel( src_gray, grad_x, ddepth, 1, 0, 3, scale, delta, cv::BORDER_DEFAULT );
00171             cv::convertScaleAbs( grad_x, abs_grad_x );
00172 
00174             //Scharr( src_gray, grad_y, ddepth, 0, 1, scale, delta, BORDER_DEFAULT );
00175             cv::Sobel( src_gray, grad_y, ddepth, 0, 1, 3, scale, delta, cv::BORDER_DEFAULT );
00176             cv::convertScaleAbs( grad_y, abs_grad_y );
00177 
00179             cv::addWeighted( abs_grad_x, 0.5, abs_grad_y, 0.5, 0, grad );
00180 
00181             new_window_name = "Sobel Edge Detection Demo";
00182             break;
00183           }
00184         case edge_detection::EdgeDetection_Laplace:
00185           {
00186             cv::Mat dst;
00187             int kernel_size = 3;
00188             int scale = 1;
00189             int delta = 0;
00190             int ddepth = CV_16S;
00192 
00193             cv::Laplacian( src_gray, dst, ddepth, kernel_size, scale, delta, cv::BORDER_DEFAULT );
00194             convertScaleAbs( dst, grad );
00195 
00196             new_window_name = "Laplace Edge Detection Demo";
00197             break;
00198           }
00199         case edge_detection::EdgeDetection_Canny:
00200           {
00201             int edgeThresh = 1;
00202             int kernel_size = 3;
00203             int const max_canny_threshold1 = 500;
00204             int const max_canny_threshold2 = 500;
00205             cv::Mat detected_edges;
00206 
00208             if(apply_blur_pre_) {
00209               cv::blur( src_gray, src_gray, cv::Size(apertureSize_, apertureSize_) );
00210             }
00211 
00213             cv::Canny( src_gray, grad, canny_threshold1_, canny_threshold2_, kernel_size, L2gradient_ );
00214             if(apply_blur_post_) {
00215               cv::GaussianBlur(grad, grad, cv::Size(postBlurSize_, postBlurSize_),
00216                                postBlurSigma_, postBlurSigma_); // 0.3*(ksize/2 - 1) + 0.8
00217             }
00218 
00219             new_window_name = "Canny Edge Detection Demo";
00220 
00222             if( debug_view_) {
00223               if (need_config_update_) {
00224                 config_.canny_threshold1 = canny_threshold1_;
00225                 config_.canny_threshold2 = canny_threshold2_;
00226                 reconfigure_server_->updateConfig(config_);
00227                 need_config_update_ = false;
00228               }
00229               if( window_name_ == new_window_name) {
00230                 cv::createTrackbar( "Min CannyThreshold1:", window_name_, &canny_threshold1_, max_canny_threshold1, trackbarCallback);
00231                 cv::createTrackbar( "Min CannyThreshold2:", window_name_, &canny_threshold2_, max_canny_threshold2, trackbarCallback);
00232               }
00233             }
00234             break;
00235           }
00236       }
00237 
00238 
00239       if( debug_view_) {
00240         if (window_name_ != new_window_name) {
00241           cv::destroyWindow(window_name_);
00242           window_name_ = new_window_name;
00243         }
00244         cv::imshow( window_name_, grad );
00245         int c = cv::waitKey(1);
00246       }
00247 
00248       // Publish the image.
00249       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, grad).toImageMsg();
00250       img_pub_.publish(out_img);
00251     }
00252     catch (cv::Exception &e)
00253     {
00254       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00255     }
00256 
00257     prev_stamp_ = msg->header.stamp;
00258   }
00259 
00260   void subscribe()
00261   {
00262     NODELET_DEBUG("Subscribing to image topic.");
00263     if (config_.use_camera_info)
00264       cam_sub_ = it_->subscribeCamera("image", 3, &EdgeDetectionNodelet::imageCallbackWithInfo, this);
00265     else
00266       img_sub_ = it_->subscribe("image", 3, &EdgeDetectionNodelet::imageCallback, this);
00267   }
00268 
00269   void unsubscribe()
00270   {
00271     NODELET_DEBUG("Unsubscribing from image topic.");
00272     img_sub_.shutdown();
00273     cam_sub_.shutdown();
00274   }
00275 
00276 public:
00277   virtual void onInit()
00278   {
00279     Nodelet::onInit();
00280     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00281 
00282     pnh_->param("debug_view", debug_view_, false);
00283 
00284     if (debug_view_) {
00285       always_subscribe_ = true;
00286     }
00287     prev_stamp_ = ros::Time(0, 0);
00288 
00289     window_name_ = "Edge Detection Demo";
00290     canny_threshold1_ = 100; // only for canny
00291     canny_threshold2_ = 200; // only for canny
00292 
00293     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00294     dynamic_reconfigure::Server<Config>::CallbackType f =
00295       boost::bind(&EdgeDetectionNodelet::reconfigureCallback, this, _1, _2);
00296     reconfigure_server_->setCallback(f);
00297 
00298     img_pub_ = advertiseImage(*pnh_, "image", 1);
00299     //msg_pub_ = local_nh_.advertise<opencv_apps::LineArrayStamped>("lines", 1, msg_connect_cb, msg_disconnect_cb);
00300 
00301     onInitPostProcess();
00302   }
00303 };
00304 bool EdgeDetectionNodelet::need_config_update_ = false;
00305 }
00306 
00307 #include <pluginlib/class_list_macros.h>
00308 PLUGINLIB_EXPORT_CLASS(edge_detection::EdgeDetectionNodelet, nodelet::Nodelet);


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