corner_harris_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) 2016, JSK Lab.
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 #include <ros/ros.h>
00036 #include "opencv_apps/nodelet.h"
00037 #include <image_transport/image_transport.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 
00041 #include <opencv2/highgui/highgui.hpp>
00042 #include <opencv2/imgproc/imgproc.hpp>
00043 
00044 #include <dynamic_reconfigure/server.h>
00045 #include "opencv_apps/CornerHarrisConfig.h"
00046 
00047 // https://github.com/opencv/opencv/blob/master/samples/cpp/tutorial_code/TrackingMotion/cornerHarris_Demo.cpp
00054 namespace opencv_apps
00055 {
00056 class CornerHarrisNodelet : public opencv_apps::Nodelet
00057 {
00058   image_transport::Publisher img_pub_;
00059   image_transport::Subscriber img_sub_;
00060   image_transport::CameraSubscriber cam_sub_;
00061   ros::Publisher msg_pub_;
00062 
00063   boost::shared_ptr<image_transport::ImageTransport> it_;
00064 
00065   typedef opencv_apps::CornerHarrisConfig Config;
00066   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00067   Config config_;
00068   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00069 
00070   int queue_size_;
00071   bool debug_view_;
00072 
00073   std::string window_name_;
00074   static bool need_config_update_;
00075 
00076   int threshold_;
00077 
00078   void reconfigureCallback(Config& new_config, uint32_t level)
00079   {
00080     config_ = new_config;
00081     threshold_ = config_.threshold;
00082   }
00083 
00084   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00085   {
00086     if (frame.empty())
00087       return image_frame;
00088     return frame;
00089   }
00090 
00091   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00092   {
00093     doWork(msg, cam_info->header.frame_id);
00094   }
00095 
00096   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00097   {
00098     doWork(msg, msg->header.frame_id);
00099   }
00100 
00101   static void trackbarCallback(int /*unused*/, void* /*unused*/)
00102   {
00103     need_config_update_ = true;
00104   }
00105 
00106   void doWork(const sensor_msgs::ImageConstPtr& image_msg, const std::string& input_frame_from_msg)
00107   {
00108     // Work on the image.
00109     try
00110     {
00111       // Convert the image into something opencv can handle.
00112       cv::Mat frame = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;
00113 
00114       // Do the work
00115       cv::Mat dst, dst_norm, dst_norm_scaled;
00116       dst = cv::Mat::zeros(frame.size(), CV_32FC1);
00117 
00118       cv::Mat src_gray;
00119 
00120       if (frame.channels() > 1)
00121       {
00122         cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
00123       }
00124       else
00125       {
00126         src_gray = frame;
00127         cv::cvtColor(src_gray, frame, cv::COLOR_GRAY2BGR);
00128       }
00129 
00131       int block_size = 2;
00132       int aperture_size = 3;
00133       double k = 0.04;
00134 
00136       cv::cornerHarris(src_gray, dst, block_size, aperture_size, k, cv::BORDER_DEFAULT);
00137 
00139       cv::normalize(dst, dst_norm, 0, 255, cv::NORM_MINMAX, CV_32FC1, cv::Mat());
00140       cv::convertScaleAbs(dst_norm, dst_norm_scaled);
00141 
00143       for (int j = 0; j < dst_norm.rows; j++)
00144       {
00145         for (int i = 0; i < dst_norm.cols; i++)
00146         {
00147           if ((int)dst_norm.at<float>(j, i) > threshold_)
00148           {
00149             cv::circle(frame, cv::Point(i, j), 5, cv::Scalar(0), 2, 8, 0);
00150           }
00151         }
00152       }
00153 
00155       if (debug_view_)
00156       {
00157         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00158         const int max_threshold = 255;
00159         if (need_config_update_)
00160         {
00161           config_.threshold = threshold_;
00162           reconfigure_server_->updateConfig(config_);
00163           need_config_update_ = false;
00164         }
00165         cv::createTrackbar("Threshold:", window_name_, &threshold_, max_threshold, trackbarCallback);
00166       }
00167 
00168       if (debug_view_)
00169       {
00170         cv::imshow(window_name_, frame);
00171         int c = cv::waitKey(1);
00172       }
00173 
00174       // Publish the image.
00175       sensor_msgs::Image::Ptr out_img =
00176           cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::BGR8, frame).toImageMsg();
00177       img_pub_.publish(out_img);
00178     }
00179     catch (cv::Exception& e)
00180     {
00181       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00182     }
00183   }
00184 
00185   void subscribe()  // NOLINT(modernize-use-override)
00186   {
00187     NODELET_DEBUG("Subscribing to image topic.");
00188     if (config_.use_camera_info)
00189       cam_sub_ = it_->subscribeCamera("image", queue_size_, &CornerHarrisNodelet::imageCallbackWithInfo, this);
00190     else
00191       img_sub_ = it_->subscribe("image", queue_size_, &CornerHarrisNodelet::imageCallback, this);
00192   }
00193 
00194   void unsubscribe()  // NOLINT(modernize-use-override)
00195   {
00196     NODELET_DEBUG("Unsubscribing from image topic.");
00197     img_sub_.shutdown();
00198     cam_sub_.shutdown();
00199   }
00200 
00201 public:
00202   virtual void onInit()  // NOLINT(modernize-use-override)
00203   {
00204     Nodelet::onInit();
00205     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00206 
00207     pnh_->param("queue_size", queue_size_, 3);
00208     pnh_->param("debug_view", debug_view_, false);
00209 
00210     if (debug_view_)
00211     {
00212       always_subscribe_ = true;
00213     }
00214 
00215     window_name_ = "CornerHarris Demo";
00216 
00217     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00218     dynamic_reconfigure::Server<Config>::CallbackType f =
00219         boost::bind(&CornerHarrisNodelet::reconfigureCallback, this, _1, _2);
00220     reconfigure_server_->setCallback(f);
00221 
00222     img_pub_ = advertiseImage(*pnh_, "image", 1);
00223 
00224     onInitPostProcess();
00225   }
00226 };
00227 bool CornerHarrisNodelet::need_config_update_ = false;
00228 }  // namespace opencv_apps
00229 
00230 namespace corner_harris
00231 {
00232 class CornerHarrisNodelet : public opencv_apps::CornerHarrisNodelet
00233 {
00234 public:
00235   virtual void onInit()  // NOLINT(modernize-use-override)
00236   {
00237     ROS_WARN("DeprecationWarning: Nodelet corner_harris/corner_harris is deprecated, "
00238              "and renamed to opencv_apps/corner_harris.");
00239     opencv_apps::CornerHarrisNodelet::onInit();
00240   }
00241 };
00242 }  // namespace corner_harris
00243 
00244 #include <pluginlib/class_list_macros.h>
00245 PLUGINLIB_EXPORT_CLASS(opencv_apps::CornerHarrisNodelet, nodelet::Nodelet);
00246 PLUGINLIB_EXPORT_CLASS(corner_harris::CornerHarrisNodelet, nodelet::Nodelet);


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