people_detect_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/peopledetect.cpp
00041 #include <ros/ros.h>
00042 #include "opencv_apps/nodelet.h"
00043 #include <image_transport/image_transport.h>
00044 #include <cv_bridge/cv_bridge.h>
00045 #include <sensor_msgs/image_encodings.h>
00046 
00047 #include <opencv2/highgui/highgui.hpp>
00048 #include <opencv2/imgproc/imgproc.hpp>
00049 #include <opencv2/objdetect/objdetect.hpp>
00050 
00051 #include <dynamic_reconfigure/server.h>
00052 #include "opencv_apps/PeopleDetectConfig.h"
00053 #include "opencv_apps/Rect.h"
00054 #include "opencv_apps/RectArrayStamped.h"
00055 
00056 namespace opencv_apps
00057 {
00058 class PeopleDetectNodelet : public opencv_apps::Nodelet
00059 {
00060   image_transport::Publisher img_pub_;
00061   image_transport::Subscriber img_sub_;
00062   image_transport::CameraSubscriber cam_sub_;
00063   ros::Publisher msg_pub_;
00064 
00065   boost::shared_ptr<image_transport::ImageTransport> it_;
00066 
00067   typedef opencv_apps::PeopleDetectConfig Config;
00068   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00069   Config config_;
00070   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00071 
00072   int queue_size_;
00073   bool debug_view_;
00074   ros::Time prev_stamp_;
00075 
00076   std::string window_name_;
00077   static bool need_config_update_;
00078 
00079   cv::HOGDescriptor hog_;
00080 
00081   double hit_threshold_;
00082   int win_stride_;
00083   int padding_;
00084   double scale0_;
00085   int group_threshold_;
00086 
00087   void reconfigureCallback(Config& new_config, uint32_t level)
00088   {
00089     config_ = new_config;
00090     hit_threshold_ = config_.hit_threshold;
00091     win_stride_ = config_.win_stride;
00092     padding_ = config_.padding;
00093     scale0_ = config_.scale0;
00094     group_threshold_ = config_.group_threshold;
00095   }
00096 
00097   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00098   {
00099     if (frame.empty())
00100       return image_frame;
00101     return frame;
00102   }
00103 
00104   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00105   {
00106     doWork(msg, cam_info->header.frame_id);
00107   }
00108 
00109   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00110   {
00111     doWork(msg, msg->header.frame_id);
00112   }
00113 
00114   static void trackbarCallback(int /*unused*/, void* /*unused*/)
00115   {
00116     need_config_update_ = true;
00117   }
00118 
00119   void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00120   {
00121     // Work on the image.
00122     try
00123     {
00124       // Convert the image into something opencv can handle.
00125       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00126 
00127       // Messages
00128       opencv_apps::RectArrayStamped found_msg;
00129       found_msg.header = msg->header;
00130 
00131       // Do the work
00132       if (debug_view_)
00133       {
00134         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00135       }
00136 
00137       std::vector<cv::Rect> found, found_filtered;
00138       double t = (double)cv::getTickCount();
00139       // run the detector with default parameters. to get a higher hit-rate
00140       // (and more false alarms, respectively), decrease the hitThreshold and
00141       // groupThreshold (set groupThreshold to 0 to turn off the grouping completely).
00142       hog_.detectMultiScale(frame, found, hit_threshold_, cv::Size(win_stride_, win_stride_),
00143                             cv::Size(padding_, padding_), scale0_, group_threshold_);
00144       t = (double)cv::getTickCount() - t;
00145       NODELET_INFO("tdetection time = %gms", t * 1000. / cv::getTickFrequency());
00146       size_t i, j;
00147       for (i = 0; i < found.size(); i++)
00148       {
00149         cv::Rect r = found[i];
00150         for (j = 0; j < found.size(); j++)
00151           if (j != i && (r & found[j]) == r)
00152             break;
00153         if (j == found.size())
00154           found_filtered.push_back(r);
00155       }
00156       for (i = 0; i < found_filtered.size(); i++)
00157       {
00158         cv::Rect r = found_filtered[i];
00159         // the HOG detector returns slightly larger rectangles than the real objects.
00160         // so we slightly shrink the rectangles to get a nicer output.
00161         r.x += cvRound(r.width * 0.1);
00162         r.width = cvRound(r.width * 0.8);
00163         r.y += cvRound(r.height * 0.07);
00164         r.height = cvRound(r.height * 0.8);
00165         cv::rectangle(frame, r.tl(), r.br(), cv::Scalar(0, 255, 0), 3);
00166 
00167         opencv_apps::Rect rect_msg;
00168         rect_msg.x = r.x;
00169         rect_msg.y = r.y;
00170         rect_msg.width = r.width;
00171         rect_msg.height = r.height;
00172         found_msg.rects.push_back(rect_msg);
00173       }
00174 
00175       //-- Show what you got
00176       if (debug_view_)
00177       {
00178         cv::imshow(window_name_, frame);
00179         int c = cv::waitKey(1);
00180       }
00181 
00182       // Publish the image.
00183       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg();
00184       img_pub_.publish(out_img);
00185       msg_pub_.publish(found_msg);
00186     }
00187     catch (cv::Exception& e)
00188     {
00189       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00190     }
00191 
00192     prev_stamp_ = msg->header.stamp;
00193   }
00194 
00195   void subscribe()  // NOLINT(modernize-use-override)
00196   {
00197     NODELET_DEBUG("Subscribing to image topic.");
00198     if (config_.use_camera_info)
00199       cam_sub_ = it_->subscribeCamera("image", queue_size_, &PeopleDetectNodelet::imageCallbackWithInfo, this);
00200     else
00201       img_sub_ = it_->subscribe("image", queue_size_, &PeopleDetectNodelet::imageCallback, this);
00202   }
00203 
00204   void unsubscribe()  // NOLINT(modernize-use-override)
00205   {
00206     NODELET_DEBUG("Unsubscribing from image topic.");
00207     img_sub_.shutdown();
00208     cam_sub_.shutdown();
00209   }
00210 
00211 public:
00212   virtual void onInit()  // NOLINT(modernize-use-override)
00213   {
00214     Nodelet::onInit();
00215     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00216 
00217     pnh_->param("queue_size", queue_size_, 3);
00218     pnh_->param("debug_view", debug_view_, false);
00219     if (debug_view_)
00220     {
00221       always_subscribe_ = true;
00222     }
00223     prev_stamp_ = ros::Time(0, 0);
00224 
00225     window_name_ = "people detector";
00226 
00227     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00228     dynamic_reconfigure::Server<Config>::CallbackType f =
00229         boost::bind(&PeopleDetectNodelet::reconfigureCallback, this, _1, _2);
00230     reconfigure_server_->setCallback(f);
00231 
00232     hog_.setSVMDetector(cv::HOGDescriptor::getDefaultPeopleDetector());
00233 
00234     img_pub_ = advertiseImage(*pnh_, "image", 1);
00235     msg_pub_ = advertise<opencv_apps::RectArrayStamped>(*pnh_, "found", 1);
00236 
00237     onInitPostProcess();
00238   }
00239 };
00240 bool PeopleDetectNodelet::need_config_update_ = false;
00241 }  // namespace opencv_apps
00242 
00243 namespace people_detect
00244 {
00245 class PeopleDetectNodelet : public opencv_apps::PeopleDetectNodelet
00246 {
00247 public:
00248   virtual void onInit()  // NOLINT(modernize-use-override)
00249   {
00250     ROS_WARN("DeprecationWarning: Nodelet people_detect/people_detect is deprecated, "
00251              "and renamed to opencv_apps/people_detect.");
00252     opencv_apps::PeopleDetectNodelet::onInit();
00253   }
00254 };
00255 }  // namespace people_detect
00256 
00257 #include <pluginlib/class_list_macros.h>
00258 PLUGINLIB_EXPORT_CLASS(opencv_apps::PeopleDetectNodelet, nodelet::Nodelet);
00259 PLUGINLIB_EXPORT_CLASS(people_detect::PeopleDetectNodelet, nodelet::Nodelet);


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