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;
90 hit_threshold_ = config_.hit_threshold;
91 win_stride_ = config_.win_stride;
92 padding_ = config_.padding;
93 scale0_ = config_.scale0;
94 group_threshold_ = config_.group_threshold;
97 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
106 doWork(msg, cam_info->header.frame_id);
111 doWork(msg, msg->header.frame_id);
116 need_config_update_ =
true;
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;
134 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
137 std::vector<cv::Rect> found, found_filtered;
138 double t = (double)cv::getTickCount();
142 hog_.detectMultiScale(frame, found, hit_threshold_, cv::Size(win_stride_, win_stride_),
143 cv::Size(padding_, padding_), scale0_, group_threshold_);
144 t = (double)cv::getTickCount() -
t;
145 NODELET_INFO(
"tdetection time = %gms", t * 1000. / cv::getTickFrequency());
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);
178 cv::imshow(window_name_, frame);
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);
192 prev_stamp_ = msg->header.stamp;
198 if (config_.use_camera_info)
217 pnh_->param(
"queue_size", queue_size_, 3);
218 pnh_->param(
"debug_view", debug_view_,
false);
225 window_name_ =
"people detector";
227 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
228 dynamic_reconfigure::Server<Config>::CallbackType
f =
230 reconfigure_server_->setCallback(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.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
boost::shared_ptr< image_transport::ImageTransport > it_
opencv_apps::PeopleDetectConfig Config
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Demo code to calculate moments.
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
PLUGINLIB_EXPORT_CLASS(opencv_apps::PeopleDetectNodelet, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
static bool need_config_update_
image_transport::Subscriber img_sub_
void reconfigureCallback(Config &new_config, uint32_t level)
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
dynamic_reconfigure::Server< Config > ReconfigureServer
#define NODELET_INFO(...)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
image_transport::Publisher img_pub_
static void trackbarCallback(int, void *)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
image_transport::CameraSubscriber cam_sub_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< ReconfigureServer > reconfigure_server_