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 opencv_apps
00066 {
00067 class EdgeDetectionNodelet : public opencv_apps::Nodelet
00068 {
00069   image_transport::Publisher img_pub_;
00070   image_transport::Subscriber img_sub_;
00071   image_transport::CameraSubscriber cam_sub_;
00072   ros::Publisher msg_pub_;
00073 
00074   boost::shared_ptr<image_transport::ImageTransport> it_;
00075 
00076   typedef opencv_apps::EdgeDetectionConfig Config;
00077   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00078   Config config_;
00079   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00080 
00081   int queue_size_;
00082   bool debug_view_;
00083   ros::Time prev_stamp_;
00084 
00085   int canny_threshold1_;
00086   int canny_threshold2_;
00087   int apertureSize_;
00088   bool L2gradient_;
00089   bool apply_blur_pre_;
00090   bool apply_blur_post_;
00091   int postBlurSize_;
00092   double postBlurSigma_;
00093 
00094   std::string window_name_;
00095   static bool need_config_update_;
00096 
00097   void reconfigureCallback(Config& new_config, uint32_t level)
00098   {
00099     config_ = new_config;
00100     canny_threshold1_ = config_.canny_threshold1;
00101     canny_threshold2_ = config_.canny_threshold2;
00102     apertureSize_ = 2 * ((config_.apertureSize / 2)) + 1;
00103     L2gradient_ = config_.L2gradient;
00104 
00105     apply_blur_pre_ = config_.apply_blur_pre;
00106     apply_blur_post_ = config_.apply_blur_post;
00107     postBlurSize_ = 2 * ((config_.postBlurSize) / 2) + 1;
00108     postBlurSigma_ = config_.postBlurSigma;
00109   }
00110 
00111   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00112   {
00113     if (frame.empty())
00114       return image_frame;
00115     return frame;
00116   }
00117 
00118   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00119   {
00120     doWork(msg, cam_info->header.frame_id);
00121   }
00122 
00123   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00124   {
00125     doWork(msg, msg->header.frame_id);
00126   }
00127 
00128   static void trackbarCallback(int /*unused*/, void* /*unused*/)
00129   {
00130     need_config_update_ = true;
00131   }
00132 
00133   void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00134   {
00135     // Work on the image.
00136     try
00137     {
00138       // Convert the image into something opencv can handle.
00139       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00140 
00141       // Do the work
00142       cv::Mat src_gray;
00143       cv::GaussianBlur(frame, frame, cv::Size(3, 3), 0, 0, cv::BORDER_DEFAULT);
00144 
00146       if (frame.channels() > 1)
00147       {
00148         cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
00149       }
00150       else
00151       {
00152         src_gray = frame;
00153       }
00154 
00156       if (debug_view_)
00157       {
00158         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00159       }
00160 
00161       std::string new_window_name;
00162       cv::Mat grad;
00163       switch (config_.edge_type)
00164       {
00165         case opencv_apps::EdgeDetection_Sobel:
00166         {
00168           cv::Mat grad_x, grad_y;
00169           cv::Mat abs_grad_x, abs_grad_y;
00170 
00171           int scale = 1;
00172           int delta = 0;
00173           int ddepth = CV_16S;
00174 
00176           // Scharr( src_gray, grad_x, ddepth, 1, 0, scale, delta, BORDER_DEFAULT );
00177           cv::Sobel(src_gray, grad_x, ddepth, 1, 0, 3, scale, delta, cv::BORDER_DEFAULT);
00178           cv::convertScaleAbs(grad_x, abs_grad_x);
00179 
00181           // Scharr( src_gray, grad_y, ddepth, 0, 1, scale, delta, BORDER_DEFAULT );
00182           cv::Sobel(src_gray, grad_y, ddepth, 0, 1, 3, scale, delta, cv::BORDER_DEFAULT);
00183           cv::convertScaleAbs(grad_y, abs_grad_y);
00184 
00186           cv::addWeighted(abs_grad_x, 0.5, abs_grad_y, 0.5, 0, grad);
00187 
00188           new_window_name = "Sobel Edge Detection Demo";
00189           break;
00190         }
00191         case opencv_apps::EdgeDetection_Laplace:
00192         {
00193           cv::Mat dst;
00194           int kernel_size = 3;
00195           int scale = 1;
00196           int delta = 0;
00197           int ddepth = CV_16S;
00199 
00200           cv::Laplacian(src_gray, dst, ddepth, kernel_size, scale, delta, cv::BORDER_DEFAULT);
00201           convertScaleAbs(dst, grad);
00202 
00203           new_window_name = "Laplace Edge Detection Demo";
00204           break;
00205         }
00206         case opencv_apps::EdgeDetection_Canny:
00207         {
00208           int edge_thresh = 1;
00209           int kernel_size = 3;
00210           int const max_canny_threshold1 = 500;
00211           int const max_canny_threshold2 = 500;
00212           cv::Mat detected_edges;
00213 
00215           if (apply_blur_pre_)
00216           {
00217             cv::blur(src_gray, src_gray, cv::Size(apertureSize_, apertureSize_));
00218           }
00219 
00221           cv::Canny(src_gray, grad, canny_threshold1_, canny_threshold2_, kernel_size, L2gradient_);
00222           if (apply_blur_post_)
00223           {
00224             cv::GaussianBlur(grad, grad, cv::Size(postBlurSize_, postBlurSize_), postBlurSigma_,
00225                              postBlurSigma_);  // 0.3*(ksize/2 - 1) + 0.8
00226           }
00227 
00228           new_window_name = "Canny Edge Detection Demo";
00229 
00231           if (debug_view_)
00232           {
00233             if (need_config_update_)
00234             {
00235               config_.canny_threshold1 = canny_threshold1_;
00236               config_.canny_threshold2 = canny_threshold2_;
00237               reconfigure_server_->updateConfig(config_);
00238               need_config_update_ = false;
00239             }
00240             if (window_name_ == new_window_name)
00241             {
00242               cv::createTrackbar("Min CannyThreshold1:", window_name_, &canny_threshold1_, max_canny_threshold1,
00243                                  trackbarCallback);
00244               cv::createTrackbar("Min CannyThreshold2:", window_name_, &canny_threshold2_, max_canny_threshold2,
00245                                  trackbarCallback);
00246             }
00247           }
00248           break;
00249         }
00250       }
00251 
00252       if (debug_view_)
00253       {
00254         if (window_name_ != new_window_name)
00255         {
00256           cv::destroyWindow(window_name_);
00257           window_name_ = new_window_name;
00258         }
00259         cv::imshow(window_name_, grad);
00260         int c = cv::waitKey(1);
00261       }
00262 
00263       // Publish the image.
00264       sensor_msgs::Image::Ptr out_img =
00265           cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, grad).toImageMsg();
00266       img_pub_.publish(out_img);
00267     }
00268     catch (cv::Exception& e)
00269     {
00270       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00271     }
00272 
00273     prev_stamp_ = msg->header.stamp;
00274   }
00275 
00276   void subscribe()  // NOLINT(modernize-use-override)
00277   {
00278     NODELET_DEBUG("Subscribing to image topic.");
00279     if (config_.use_camera_info)
00280       cam_sub_ = it_->subscribeCamera("image", queue_size_, &EdgeDetectionNodelet::imageCallbackWithInfo, this);
00281     else
00282       img_sub_ = it_->subscribe("image", queue_size_, &EdgeDetectionNodelet::imageCallback, this);
00283   }
00284 
00285   void unsubscribe()  // NOLINT(modernize-use-override)
00286   {
00287     NODELET_DEBUG("Unsubscribing from image topic.");
00288     img_sub_.shutdown();
00289     cam_sub_.shutdown();
00290   }
00291 
00292 public:
00293   virtual void onInit()  // NOLINT(modernize-use-override)
00294   {
00295     Nodelet::onInit();
00296     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00297 
00298     pnh_->param("queue_size", queue_size_, 3);
00299     pnh_->param("debug_view", debug_view_, false);
00300 
00301     if (debug_view_)
00302     {
00303       always_subscribe_ = true;
00304     }
00305     prev_stamp_ = ros::Time(0, 0);
00306 
00307     window_name_ = "Edge Detection Demo";
00308     canny_threshold1_ = 100;  // only for canny
00309     canny_threshold2_ = 200;  // only for canny
00310 
00311     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00312     dynamic_reconfigure::Server<Config>::CallbackType f =
00313         boost::bind(&EdgeDetectionNodelet::reconfigureCallback, this, _1, _2);
00314     reconfigure_server_->setCallback(f);
00315 
00316     img_pub_ = advertiseImage(*pnh_, "image", 1);
00317     // msg_pub_ = local_nh_.advertise<opencv_apps::LineArrayStamped>("lines", 1, msg_connect_cb, msg_disconnect_cb);
00318 
00319     onInitPostProcess();
00320   }
00321 };
00322 bool EdgeDetectionNodelet::need_config_update_ = false;
00323 }  // namespace opencv_apps
00324 
00325 namespace edge_detection
00326 {
00327 class EdgeDetectionNodelet : public opencv_apps::EdgeDetectionNodelet
00328 {
00329 public:
00330   virtual void onInit()  // NOLINT(modernize-use-override)
00331   {
00332     ROS_WARN("DeprecationWarning: Nodelet edge_detection/edge_detection is deprecated, "
00333              "and renamed to opencv_apps/edge_detection.");
00334     opencv_apps::EdgeDetectionNodelet::onInit();
00335   }
00336 };
00337 }  // namespace edge_detection
00338 
00339 #include <pluginlib/class_list_macros.h>
00340 PLUGINLIB_EXPORT_CLASS(opencv_apps::EdgeDetectionNodelet, nodelet::Nodelet);
00341 PLUGINLIB_EXPORT_CLASS(edge_detection::EdgeDetectionNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26