face_detection_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Kei Okada.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/objectDetection/objectDetection.cpp
43 #include <ros/ros.h>
44 #include "opencv_apps/nodelet.h"
46 #include <cv_bridge/cv_bridge.h>
48 
49 #include <opencv2/objdetect/objdetect.hpp>
50 #include <opencv2/highgui/highgui.hpp>
51 #include <opencv2/imgproc/imgproc.hpp>
52 
53 #include <dynamic_reconfigure/server.h>
54 #include "opencv_apps/FaceDetectionConfig.h"
55 #include "opencv_apps/Face.h"
56 #include "opencv_apps/FaceArray.h"
57 #include "opencv_apps/FaceArrayStamped.h"
58 
59 namespace opencv_apps
60 {
62 {
68 
70 
71  typedef opencv_apps::FaceDetectionConfig Config;
72  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
73  Config config_;
75 
79 
80  cv::CascadeClassifier face_cascade_;
81  cv::CascadeClassifier eyes_cascade_;
82 
83  void reconfigureCallback(Config& new_config, uint32_t level)
84  {
85  config_ = new_config;
86  }
87 
88  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
89  {
90  if (frame.empty())
91  return image_frame;
92  return frame;
93  }
94 
95  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
96  {
97  doWork(msg, cam_info->header.frame_id);
98  }
99 
100  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
101  {
102  doWork(msg, msg->header.frame_id);
103  }
104 
105  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
106  {
107  // Work on the image.
108  try
109  {
110  // Convert the image into something opencv can handle.
111  cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
112 
113  // Messages
114  opencv_apps::FaceArrayStamped faces_msg;
115  faces_msg.header = msg->header;
116 
117  // Do the work
118  std::vector<cv::Rect> faces;
119  cv::Mat frame_gray;
120 
121  if (frame.channels() > 1)
122  {
123  cv::cvtColor(frame, frame_gray, cv::COLOR_BGR2GRAY);
124  }
125  else
126  {
127  frame_gray = frame;
128  }
129  cv::equalizeHist(frame_gray, frame_gray);
130 //-- Detect faces
131 #ifndef CV_VERSION_EPOCH
132  face_cascade_.detectMultiScale(frame_gray, faces, 1.1, 2, 0, cv::Size(30, 30));
133 #else
134  face_cascade_.detectMultiScale(frame_gray, faces, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30));
135 #endif
136 
137  cv::Mat face_image;
138  if (!faces.empty())
139  {
140  cv::Rect max_area = faces[0];
141  for (const cv::Rect& face : faces)
142  {
143  if (max_area.width * max_area.height > face.width * face.height)
144  {
145  max_area = face;
146  }
147  }
148  face_image = frame(max_area).clone();
149  }
150 
151  for (const cv::Rect& face : faces)
152  {
153  cv::Point center(face.x + face.width / 2, face.y + face.height / 2);
154  cv::ellipse(frame, center, cv::Size(face.width / 2, face.height / 2), 0, 0, 360, cv::Scalar(255, 0, 255), 2, 8,
155  0);
156  opencv_apps::Face face_msg;
157  face_msg.face.x = center.x;
158  face_msg.face.y = center.y;
159  face_msg.face.width = face.width;
160  face_msg.face.height = face.height;
161 
162  cv::Mat face_roi = frame_gray(face);
163  std::vector<cv::Rect> eyes;
164 
165 //-- In each face, detect eyes
166 #ifndef CV_VERSION_EPOCH
167  eyes_cascade_.detectMultiScale(face_roi, eyes, 1.1, 2, 0, cv::Size(30, 30));
168 #else
169  eyes_cascade_.detectMultiScale(face_roi, eyes, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30));
170 #endif
171 
172  for (const cv::Rect& eye : eyes)
173  {
174  cv::Point eye_center(face.x + eye.x + eye.width / 2, face.y + eye.y + eye.height / 2);
175  int radius = cvRound((eye.width + eye.height) * 0.25);
176  cv::circle(frame, eye_center, radius, cv::Scalar(255, 0, 0), 3, 8, 0);
177 
178  opencv_apps::Rect eye_msg;
179  eye_msg.x = eye_center.x;
180  eye_msg.y = eye_center.y;
181  eye_msg.width = eye.width;
182  eye_msg.height = eye.height;
183  face_msg.eyes.push_back(eye_msg);
184  }
185 
186  faces_msg.faces.push_back(face_msg);
187  }
188  //-- Show what you got
189  if (debug_view_)
190  {
191  cv::imshow("Face detection", frame);
192  int c = cv::waitKey(1);
193  }
194 
195  // Publish the image.
196  sensor_msgs::Image::Ptr out_img =
198  img_pub_.publish(out_img);
199  msg_pub_.publish(faces_msg);
200  if (!faces.empty())
201  {
202  sensor_msgs::Image::Ptr out_face_img =
204  face_img_pub_.publish(out_face_img);
205  }
206  }
207  catch (cv::Exception& e)
208  {
209  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
210  }
211 
212  prev_stamp_ = msg->header.stamp;
213  }
214 
215  void subscribe() // NOLINT(modernize-use-override)
216  {
217  NODELET_DEBUG("Subscribing to image topic.");
218  if (config_.use_camera_info)
219  cam_sub_ = it_->subscribeCamera("image", queue_size_, &FaceDetectionNodelet::imageCallbackWithInfo, this);
220  else
221  img_sub_ = it_->subscribe("image", queue_size_, &FaceDetectionNodelet::imageCallback, this);
222  }
223 
224  void unsubscribe() // NOLINT(modernize-use-override)
225  {
226  NODELET_DEBUG("Unsubscribing from image topic.");
227  img_sub_.shutdown();
228  cam_sub_.shutdown();
229  }
230 
231 public:
232  virtual void onInit() // NOLINT(modernize-use-override)
233  {
234  Nodelet::onInit();
236 
237  pnh_->param("queue_size", queue_size_, 3);
238  pnh_->param("debug_view", debug_view_, false);
239  if (debug_view_)
240  {
241  always_subscribe_ = true;
242  }
243  prev_stamp_ = ros::Time(0, 0);
244 
245  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
246  dynamic_reconfigure::Server<Config>::CallbackType f =
247  boost::bind(&FaceDetectionNodelet::reconfigureCallback, this, _1, _2);
248  reconfigure_server_->setCallback(f);
249 
250  img_pub_ = advertiseImage(*pnh_, "image", 1);
251  face_img_pub_ = advertiseImage(*pnh_, "face_image", 1);
252  msg_pub_ = advertise<opencv_apps::FaceArrayStamped>(*pnh_, "faces", 1);
253 
254  std::string face_cascade_name, eyes_cascade_name;
255  pnh_->param("face_cascade_name", face_cascade_name,
256  std::string("/usr/share/opencv/haarcascades/haarcascade_frontalface_alt.xml"));
257  pnh_->param("eyes_cascade_name", eyes_cascade_name,
258  std::string("/usr/share/opencv/haarcascades/haarcascade_eye_tree_eyeglasses.xml"));
259 
260  if (!face_cascade_.load(face_cascade_name))
261  {
262  NODELET_ERROR("--Error loading %s", face_cascade_name.c_str());
263  };
264  if (!eyes_cascade_.load(eyes_cascade_name))
265  {
266  NODELET_ERROR("--Error loading %s", eyes_cascade_name.c_str());
267  };
268 
270  }
271 };
272 } // namespace opencv_apps
273 
274 namespace face_detection
275 {
277 {
278 public:
279  virtual void onInit() // NOLINT(modernize-use-override)
280  {
281  ROS_WARN("DeprecationWarning: Nodelet face_detection/face_detection is deprecated, "
282  "and renamed to opencv_apps/face_detection.");
284  }
285 };
286 } // namespace face_detection
287 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
#define NODELET_ERROR(...)
void reconfigureCallback(Config &new_config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
f
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
Demo code to calculate moments.
Definition: nodelet.h:48
opencv_apps::FaceDetectionConfig Config
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
#define ROS_WARN(...)
image_transport::CameraSubscriber cam_sub_
boost::shared_ptr< image_transport::ImageTransport > it_
dynamic_reconfigure::Server< Config > ReconfigureServer
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:57
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:40
void publish(const sensor_msgs::Image &message) const
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
image_transport::Publisher face_img_pub_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
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...
Definition: nodelet.h:180
PLUGINLIB_EXPORT_CLASS(opencv_apps::FaceDetectionNodelet, nodelet::Nodelet)
image_transport::Subscriber img_sub_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const


opencv_apps
Author(s): Kei Okada
autogenerated on Sat Aug 22 2020 03:35:08