47 #include <opencv2/highgui/highgui.hpp>
48 #include <opencv2/imgproc/imgproc.hpp>
49 #include <opencv2/objdetect/objdetect.hpp>
51 #include <dynamic_reconfigure/server.h>
52 #include "opencv_apps/PeopleDetectConfig.h"
53 #include "opencv_apps/Rect.h"
54 #include "opencv_apps/RectArrayStamped.h"
67 typedef opencv_apps::PeopleDetectConfig
Config;
79 cv::HOGDescriptor
hog_;
97 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
104 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
106 doWork(msg, cam_info->header.frame_id);
111 doWork(msg, msg->header.frame_id);
119 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
128 opencv_apps::RectArrayStamped found_msg;
129 found_msg.header = msg->header;
137 std::vector<cv::Rect> found, found_filtered;
138 double t = (double)cv::getTickCount();
144 t = (double)cv::getTickCount() -
t;
147 for (i = 0; i < found.size(); i++)
149 cv::Rect r = found[i];
150 for (j = 0; j < found.size(); j++)
151 if (j != i && (r & found[j]) == r)
153 if (j == found.size())
154 found_filtered.push_back(r);
156 for (i = 0; i < found_filtered.size(); i++)
158 cv::Rect r = found_filtered[i];
161 r.x += cvRound(r.width * 0.1);
162 r.width = cvRound(r.width * 0.8);
163 r.y += cvRound(r.height * 0.07);
164 r.height = cvRound(r.height * 0.8);
165 cv::rectangle(frame, r.tl(), r.br(), cv::Scalar(0, 255, 0), 3);
167 opencv_apps::Rect rect_msg;
170 rect_msg.width = r.width;
171 rect_msg.height = r.height;
172 found_msg.rects.push_back(rect_msg);
179 int c = cv::waitKey(1);
187 catch (cv::Exception& e)
189 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
228 dynamic_reconfigure::Server<Config>::CallbackType
f =
232 hog_.setSVMDetector(cv::HOGDescriptor::getDefaultPeopleDetector());
235 msg_pub_ = advertise<opencv_apps::RectArrayStamped>(*
pnh_,
"found", 1);
250 ROS_WARN(
"DeprecationWarning: Nodelet people_detect/people_detect is deprecated, "
251 "and renamed to opencv_apps/people_detect.");
257 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H