00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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 people_detect {
00057 class PeopleDetectNodelet : 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 people_detect::PeopleDetectConfig 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 cv::HOGDescriptor hog_;
00078
00079 double hit_threshold_;
00080 int win_stride_;
00081 int padding_;
00082 double scale0_;
00083 int group_threshold_;
00084
00085 void reconfigureCallback(Config &new_config, uint32_t level)
00086 {
00087 config_ = new_config;
00088 hit_threshold_ = config_.hit_threshold;
00089 win_stride_ = config_.win_stride;
00090 padding_ = config_.padding;
00091 scale0_ = config_.scale0;
00092 group_threshold_ = config_.group_threshold;
00093 }
00094
00095 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00096 {
00097 if (frame.empty())
00098 return image_frame;
00099 return frame;
00100 }
00101
00102 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00103 {
00104 do_work(msg, cam_info->header.frame_id);
00105 }
00106
00107 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00108 {
00109 do_work(msg, msg->header.frame_id);
00110 }
00111
00112 static void trackbarCallback( int, void* )
00113 {
00114 need_config_update_ = true;
00115 }
00116
00117 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00118 {
00119
00120 try
00121 {
00122
00123 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00124
00125
00126 opencv_apps::RectArrayStamped found_msg;
00127 found_msg.header = msg->header;
00128
00129
00130 if( debug_view_) {
00131 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00132 }
00133
00134 std::vector<cv::Rect> found, found_filtered;
00135 double t = (double)cv::getTickCount();
00136
00137
00138
00139 hog_.detectMultiScale(frame, found, hit_threshold_, cv::Size(win_stride_, win_stride_), cv::Size(padding_, padding_), scale0_, group_threshold_);
00140 t = (double)cv::getTickCount() - t;
00141 NODELET_INFO("tdetection time = %gms", t*1000./cv::getTickFrequency());
00142 size_t i, j;
00143 for( i = 0; i < found.size(); i++ )
00144 {
00145 cv::Rect r = found[i];
00146 for( j = 0; j < found.size(); j++ )
00147 if( j != i && (r & found[j]) == r)
00148 break;
00149 if( j == found.size() )
00150 found_filtered.push_back(r);
00151 }
00152 for( i = 0; i < found_filtered.size(); i++ )
00153 {
00154 cv::Rect r = found_filtered[i];
00155
00156
00157 r.x += cvRound(r.width*0.1);
00158 r.width = cvRound(r.width*0.8);
00159 r.y += cvRound(r.height*0.07);
00160 r.height = cvRound(r.height*0.8);
00161 cv::rectangle(frame, r.tl(), r.br(), cv::Scalar(0,255,0), 3);
00162
00163 opencv_apps::Rect rect_msg;
00164 rect_msg.x = r.x;
00165 rect_msg.y = r.y;
00166 rect_msg.width = r.width;
00167 rect_msg.height = r.height;
00168 found_msg.rects.push_back(rect_msg);
00169 }
00170
00171
00172 if( debug_view_) {
00173 cv::imshow( window_name_, frame );
00174 int c = cv::waitKey(1);
00175 }
00176
00177
00178 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding,frame).toImageMsg();
00179 img_pub_.publish(out_img);
00180 msg_pub_.publish(found_msg);
00181 }
00182 catch (cv::Exception &e)
00183 {
00184 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00185 }
00186
00187 prev_stamp_ = msg->header.stamp;
00188 }
00189
00190 void subscribe()
00191 {
00192 NODELET_DEBUG("Subscribing to image topic.");
00193 if (config_.use_camera_info)
00194 cam_sub_ = it_->subscribeCamera("image", 3, &PeopleDetectNodelet::imageCallbackWithInfo, this);
00195 else
00196 img_sub_ = it_->subscribe("image", 3, &PeopleDetectNodelet::imageCallback, this);
00197 }
00198
00199 void unsubscribe()
00200 {
00201 NODELET_DEBUG("Unsubscribing from image topic.");
00202 img_sub_.shutdown();
00203 cam_sub_.shutdown();
00204 }
00205
00206 public:
00207 virtual void onInit()
00208 {
00209 Nodelet::onInit();
00210 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00211
00212 pnh_->param("debug_view", debug_view_, false);
00213 if (debug_view_) {
00214 always_subscribe_ = true;
00215 }
00216 prev_stamp_ = ros::Time(0, 0);
00217
00218 window_name_ = "people detector";
00219
00220 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00221 dynamic_reconfigure::Server<Config>::CallbackType f =
00222 boost::bind(&PeopleDetectNodelet::reconfigureCallback, this, _1, _2);
00223 reconfigure_server_->setCallback(f);
00224
00225 hog_.setSVMDetector(cv::HOGDescriptor::getDefaultPeopleDetector());
00226
00227 img_pub_ = advertiseImage(*pnh_, "image", 1);
00228 msg_pub_ = advertise<opencv_apps::RectArrayStamped>(*pnh_, "found", 1);
00229
00230 onInitPostProcess();
00231 }
00232 };
00233 bool PeopleDetectNodelet::need_config_update_ = false;
00234 }
00235
00236 #include <pluginlib/class_list_macros.h>
00237 PLUGINLIB_EXPORT_CLASS(people_detect::PeopleDetectNodelet, nodelet::Nodelet);