[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

pi_vision: pi_face_tracker | pi_face_tracker_gui | ros2opencv

Package Summary

A ROS node for face tracking or tracking an arbitrarily selected patch in a video stream.

pi_vision: pi_face_tracker | pi_face_tracker_gui | ros2opencv

Package Summary

A ROS node for face tracking or tracking an arbitrarily selected patch in a video stream.

pi_vision: pi_face_tracker | pi_face_tracker_gui | ros2opencv

Package Summary

A ROS node for face tracking or tracking an arbitrarily selected patch in a video stream.

Depreciated

Please note that this package is no longer being maintained. The same functionality can be found in the rbx1_vision package in the ROS By Example repository which is actively maintained and currently available through ROS Indigo.

Overview

The pi_face_tracker ROS package uses OpenCV's Haar face detector together with Good Features to Track and the Lucas-Kanade Optical Flow tracker to perform face tracking in a live video stream or recorded video file. Works best with an RGB-D camera such as the Kinect so that depth information can be used to reduce the number of false positive face detections.

In the video above from the Honda/UCSD Video Database, the left image uses only the Haar face detector while the right image uses the detector only on the first frame to get the initial face region, then relies on Good Features to Track and Optical Flow to follow the face through the rest of the video. Notice that the right video never loses the face and runs about three times faster (CPS = "cycles per second").

How It Works

When running in automatic face detection mode, the video is scanned using three of the OpenCV Haar face detectors, two frontal cascades and one profile cascade (see HaarDetectObjects). Once a face is detected, the GoodFeaturesToTrack filter is run over the face region to extract a collection of points to track. These points are then fed to the Lucas-Kanade Optical Flow Tracker CalcOpticalFlowPyrLK which follows the points from one frame to the next.

Over time, feature points will be lost due to occlusions or picked up from the background. Therefore, two additional methods are run to maintain the integrity of the tracked feature cluster. First, feature points are pruned (dropped) if they lie too far outside the current cluster in the x-y camera plane (see parameter ~std_err_xy) or in depth (see ~use_depth_for_tracking). At the same time, new feature points are added by expanding the current cluster ROI by a small amount (10%) and running GoodFeaturesToTrack over the expanded region. If the feature cluster shrinks below a specified minimum number of points (see ~abs_min_features), the algorithm returns to the Haar face detector and scans the video to relocate the face.

When not using automatic face detection, the only difference from above is that the original region to track is defined by the user by dragging a rectangle over a part of the image.

Installation Instructions

First install Eric Perko's uvc_cam package if you don't have it already:

$ git clone https://github.com/ericperko/uvc_cam.git
$ rosdep install uvc_cam
$ rosmake uvc_cam

For rosdep and rosmake to work, new packages need to be on your ROS_PACKAGE_PATH. So clone them into your sandbox, or use rosws (do not forget to source setup.sh), or change your ROS_PACKAGE_PATH manually.

Next, install the pi_vision stack as follows:

$ svn co http://pi-robot-ros-pkg.googlecode.com/svn/trunk/pi_vision
$ rosmake pi_vision

How To Use

Note: Best results are obtained at video resolutions of 640x480 or higher. Lower resolutions will work OK if the face is not too far away from the camera.

Keyboard Commands Once Tracking Has Started

First make sure the video window is in the foreground (click on the title bar). Then type one of the following characters:

Tracking with the Kinect RGB-D Camera

$ roslaunch ros2opencv openni_node.launch

Then launch the Kinect face tracker launch file:

$ roslaunch pi_face_tracker face_tracker_kinect.launch 

Tracking with a UVC-Compatible Webcam

If you have only one webcam attached to your computer and it is device /dev/video0, then simply launch:

$ roslaunch ros2opencv uvc_cam.launch

To connect to a different device, e.g. /dev/video1, use the following form:

$ roslaunch ros2opencv uvc_cam.launch device:=/dev/video1

Then launch the UVC face tracker launch file:

$ roslaunch pi_face_tracker face_tracker_uvc_cam.launch 

Tracking with an AVI File

$ roslaunch pi_face_tracker face_tracker_uvc_cam.launch 

Then start the video file:

$ roslaunch ros2opencv avi2ros.launch input:=/path/to/avi/file

Special Keyboard Commands for AVI Files

First make sure the video window is in the foreground (click on the title bar):

Tracking a Non-Face Video Patch

To track objects other than faces, first turn off face tracking either by typing the letter 'a' in the image window or by setting the auto_face_tracking parameter to False in the appropriate launch file and re-running the launch file. Then use your mouse to draw a box around the object you want to track. You can select a different patch at any time.

Nodes

pi_face_tracker.py

A ROS node for face tracking using the OpenCV face detector together with Good Features to Track and the Lucas-Kanade Optical Flow tracker.

Subscribed Topics

~input_rgb_image (sensor_msgs/Image) ~input_depth_image (sensor_msgs/Image)

Published Topics

/roi (sensor_msgs/RegionOfInterest) /target_point (geometry_msgs/PointStamped)

Services

~key_command (pi_face_tracker/KeyCommand) ~set_roi (pi_face_tracker/SetROI)

Parameters

~auto_face_tracking (boolean, default: True) ~use_haar_only (boolean, default: False) ~use_depth_for_detection (boolean, default: True) ~use_depth_for_tracking (boolean, default: False) ~auto_min_features (boolean, default: True) ~min_features (int, default: 50) ~abs_min_features (int, default: 6) ~good_feature_distance (int, default: 5) ~add_feature_distance (int, default: 10) ~std_err_xy (float, default: 2.5) ~pct_err_z (float, default: 0.42) ~max_mse (float, default: 100000) ~show_text (str, default: True) ~show_features (str, default: True) ~max_face_size (float, default: 0.28) ~expand_roi (float, default: 1.02) ~fov_width (float, default: 1.094) ~fov_height (float, default: 1.094) ~flip_image (boolean, default: False) ~feature_type (int, default: 0)


2019-07-20 13:00