goodfeature_track_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 // http://github.com/Itseez/opencv/blob/master/samples/cpp/tutorial_code/TrackingMotion/goodFeaturesToTrack_Demo.cpp
00042 #include <ros/ros.h>
00043 #include "opencv_apps/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 #include <dynamic_reconfigure/server.h>
00052 #include "opencv_apps/GoodfeatureTrackConfig.h"
00053 #include "opencv_apps/Point2D.h"
00054 #include "opencv_apps/Point2DArrayStamped.h"
00055 
00056 namespace goodfeature_track {
00057 class GoodfeatureTrackNodelet : public opencv_apps::Nodelet
00058 {
00059   image_transport::Publisher img_pub_;
00060   image_transport::Subscriber img_sub_;
00061   image_transport::CameraSubscriber cam_sub_;
00062   ros::Publisher msg_pub_;
00063 
00064   boost::shared_ptr<image_transport::ImageTransport> it_;
00065 
00066   typedef goodfeature_track::GoodfeatureTrackConfig Config;
00067   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00068   Config config_;
00069   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00070 
00071   bool debug_view_;
00072   ros::Time prev_stamp_;
00073 
00074   std::string window_name_;
00075   static bool need_config_update_;
00076 
00077   int max_corners_;
00078 
00079   void reconfigureCallback(Config &new_config, uint32_t level)
00080   {
00081     config_ = new_config;
00082     max_corners_ = config_.max_corners;
00083   }
00084 
00085   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00086   {
00087     if (frame.empty())
00088       return image_frame;
00089     return frame;
00090   }
00091 
00092   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00093   {
00094     do_work(msg, cam_info->header.frame_id);
00095   }
00096 
00097   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00098   {
00099     do_work(msg, msg->header.frame_id);
00100   }
00101 
00102   static void trackbarCallback( int, void* )
00103   {
00104     need_config_update_ = true;
00105   }
00106 
00107   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00108   {
00109     // Work on the image.
00110     try
00111     {
00112       // Convert the image into something opencv can handle.
00113       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00114 
00115       // Messages
00116       opencv_apps::Point2DArrayStamped corners_msg;
00117       corners_msg.header = msg->header;
00118 
00119       // Do the work
00120       cv::Mat src_gray;
00121       int maxTrackbar = 100;
00122 
00123       if ( frame.channels() > 1 ) {
00124         cv::cvtColor( frame, src_gray, cv::COLOR_BGR2GRAY );
00125       } else {
00126         src_gray = frame;
00127         cv::cvtColor( src_gray, frame, cv::COLOR_GRAY2BGR );
00128       }
00129 
00130       if( debug_view_) {
00132         cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00133         cv::createTrackbar( "Max corners", window_name_, &max_corners_, maxTrackbar, trackbarCallback);
00134         if (need_config_update_) {
00135           config_.max_corners = max_corners_;
00136           reconfigure_server_->updateConfig(config_);
00137           need_config_update_ = false;
00138         }
00139       }
00140 
00142       if( max_corners_ < 1 ) { max_corners_ = 1; }
00143 
00145       std::vector<cv::Point2f> corners;
00146       double qualityLevel = 0.01;
00147       double minDistance = 10;
00148       int blockSize = 3;
00149       bool useHarrisDetector = false;
00150       double k = 0.04;
00151 
00152       cv::RNG rng(12345);
00153 
00155       cv::goodFeaturesToTrack( src_gray,
00156                                corners,
00157                                max_corners_,
00158                                qualityLevel,
00159                                minDistance,
00160                                cv::Mat(),
00161                                blockSize,
00162                                useHarrisDetector,
00163                                k );
00164 
00165 
00167       NODELET_INFO_STREAM("** Number of corners detected: "<<corners.size());
00168       int r = 4;
00169       for( size_t i = 0; i < corners.size(); i++ )
00170       { cv::circle( frame, corners[i], r, cv::Scalar(rng.uniform(0,255), rng.uniform(0,255), rng.uniform(0,255)), -1, 8, 0 ); }
00171 
00172       //-- Show what you got
00173       if( debug_view_) {
00174         cv::imshow( window_name_, frame );
00175         int c = cv::waitKey(1);
00176       }
00177 
00178       // Create msgs
00179       for( size_t i = 0; i< corners.size(); i++ ) {
00180         opencv_apps::Point2D corner;
00181         corner.x = corners[i].x;
00182         corner.y = corners[i].y;
00183         corners_msg.points.push_back(corner);
00184       }
00185       // Publish the image.
00186       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", frame).toImageMsg();
00187       img_pub_.publish(out_img);
00188       msg_pub_.publish(corners_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, &GoodfeatureTrackNodelet::imageCallbackWithInfo, this);
00203     else
00204       img_sub_ = it_->subscribe("image", 3, &GoodfeatureTrackNodelet::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 public:
00215   virtual void onInit()
00216   {
00217     Nodelet::onInit();
00218     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00219 
00220     pnh_->param("debug_view", debug_view_, false);
00221     if (debug_view_) {
00222       always_subscribe_ = true;
00223     }
00224     prev_stamp_ = ros::Time(0, 0);
00225 
00226     window_name_ = "Image";
00227     max_corners_ = 23;
00228 
00229     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00230     dynamic_reconfigure::Server<Config>::CallbackType f =
00231       boost::bind(&GoodfeatureTrackNodelet::reconfigureCallback, this, _1, _2);
00232     reconfigure_server_->setCallback(f);
00233     
00234     img_pub_ = advertiseImage(*pnh_, "image", 1);
00235     msg_pub_ = advertise<opencv_apps::Point2DArrayStamped>(*pnh_, "corners", 1);
00236 
00237     onInitPostProcess();
00238   }
00239 };
00240 bool GoodfeatureTrackNodelet::need_config_update_ = false;
00241 }
00242 
00243 #include <pluginlib/class_list_macros.h>
00244 PLUGINLIB_EXPORT_CLASS(goodfeature_track::GoodfeatureTrackNodelet, nodelet::Nodelet);


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