people: face_detector | people_msgs
Package Summary
Face detection in images.
- Author: Caroline Pantofaru
- License: BSD
- Repository: wg-ros-pkg
- Source: svn https://code.ros.org/svn/wg-ros-pkg/stacks/people/trunk/face_detector
Contents
Overview
Provides detections of faces in stereo camera data. The face detector employs the OpenCV face detector (based on a cascade of Haar-like features) to obtain an initial set of detections. It then prunes false positives using stereo depth information. The depth information is used to predict the real-world size of the detected face, which is then preserved as a true face detection only if the size is realistic for a human face. This removes the majority of false positives given by the OpenCV detector.
In the two images below, all of the bounding boxes are detections from the OpenCV frontal face detector. The blue detection does not have sufficient depth information (due to low illumination) and hence will be considered a false positive by the face_detector node. The red detection has an unrealistic real-world size, and will be considered a false positive. Only the green detections are returned as true face detections.
Node
face_detector
The face_detector node can be used in two ways, continuously or as an action. Continuous mode: detect faces in the entire image stream. Action mode: an action is used to start face detection. The detector process images until it has found at least one face.Action Result
face_positions (people_msgs/PositionMeasurement)- A list of found faces.
Subscribed Topics
<stereo>/left/<image> (sensor_msgs/Image)- The image from the left camera in the stereo pair. Should be de-bayered and rectified. Can be color or grayscale.
- The disparity image.
- The camera parameters from the left camera.
- The camera parameters from the right camera.
Published Topics
face_detector/people_tracker_measurements (people_msgs/PositionMeasurement)- The 3D position of the center of the face. Fields are available for reliability and covariance measurements if desired.
- A point cloud of face centers, intended for visualization.
Parameters
~classifier_name (string)- A readable string for the classifier. Will be published with the result.
- Full path to the trained haar cascade. Provided classifiers are in opencv2. We recommend using the haar_frontalface_alt.xml
- Some notion of the classifier's reliability for use in a larger system.
- true=run continuously, false=wait for action call
- true = If depth info is not available, just make pos.x and pos.y in the resulting people_msgs/PositionMeasurement messaging the 2D image center of the face. false = Don't publish faces if stereo information isn't available.
- none = Don't display anything. local = display in an OpenCV window.
- The minimum width of a face, in meters. Defaults to 0.1m.
- The maximum width of a face, in meters. Defaults to 0.5m.
- The maximum distance of a face from the camera, in meters. (In the camera frame, depth is along the z-axis.) Defaults to 8.0m.
- Only used for tracking. The maximum distance between two face detections before they are considered different faces. Defaults to 1.0m.
Example Usage
See face_detector/launch/face_detector.wide.launch to see how to run the face detector continuously, or face_detector/launch/face_detector_action.wide.launch to run it as an action.






