49 #include <opencv2/objdetect/objdetect.hpp> 50 #include <opencv2/highgui/highgui.hpp> 51 #include <opencv2/imgproc/imgproc.hpp> 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" 71 typedef opencv_apps::FaceDetectionConfig
Config;
88 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
95 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
97 doWork(msg, cam_info->header.frame_id);
102 doWork(msg, msg->header.frame_id);
105 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
114 opencv_apps::FaceArrayStamped faces_msg;
115 faces_msg.header = msg->header;
118 std::vector<cv::Rect> faces;
121 if (frame.channels() > 1)
123 cv::cvtColor(frame, frame_gray, cv::COLOR_BGR2GRAY);
129 cv::equalizeHist(frame_gray, frame_gray);
131 #ifndef CV_VERSION_EPOCH 132 face_cascade_.detectMultiScale(frame_gray, faces, 1.1, 2, 0, cv::Size(30, 30));
134 face_cascade_.detectMultiScale(frame_gray, faces, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30));
140 cv::Rect max_area = faces[0];
141 for (
const cv::Rect& face : faces)
143 if (max_area.width * max_area.height > face.width * face.height)
148 face_image = frame(max_area).clone();
151 for (
const cv::Rect& face : faces)
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,
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;
162 cv::Mat face_roi = frame_gray(face);
163 std::vector<cv::Rect> eyes;
166 #ifndef CV_VERSION_EPOCH 167 eyes_cascade_.detectMultiScale(face_roi, eyes, 1.1, 2, 0, cv::Size(30, 30));
169 eyes_cascade_.detectMultiScale(face_roi, eyes, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30));
172 for (
const cv::Rect& eye : eyes)
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);
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);
186 faces_msg.faces.push_back(face_msg);
191 cv::imshow(
"Face detection", frame);
192 int c = cv::waitKey(1);
196 sensor_msgs::Image::Ptr out_img =
202 sensor_msgs::Image::Ptr out_face_img =
204 face_img_pub_.
publish(out_face_img);
207 catch (cv::Exception& e)
209 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
212 prev_stamp_ = msg->header.stamp;
218 if (config_.use_camera_info)
237 pnh_->param(
"queue_size", queue_size_, 3);
238 pnh_->param(
"debug_view", debug_view_,
false);
245 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
246 dynamic_reconfigure::Server<Config>::CallbackType
f =
248 reconfigure_server_->setCallback(f);
252 msg_pub_ = advertise<opencv_apps::FaceArrayStamped>(*
pnh_,
"faces", 1);
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"));
260 if (!face_cascade_.load(face_cascade_name))
262 NODELET_ERROR(
"--Error loading %s", face_cascade_name.c_str());
264 if (!eyes_cascade_.load(eyes_cascade_name))
266 NODELET_ERROR(
"--Error loading %s", eyes_cascade_name.c_str());
281 ROS_WARN(
"DeprecationWarning: Nodelet face_detection/face_detection is deprecated, " 282 "and renamed to opencv_apps/face_detection.");
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
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
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.
opencv_apps::FaceDetectionConfig Config
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
cv::CascadeClassifier eyes_cascade_
image_transport::CameraSubscriber cam_sub_
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Publisher img_pub_
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...
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
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.
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...
cv::CascadeClassifier face_cascade_
PLUGINLIB_EXPORT_CLASS(opencv_apps::FaceDetectionNodelet, nodelet::Nodelet)
image_transport::Subscriber img_sub_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const