Classes | Public Types | Public Member Functions | Public Attributes | Private Member Functions
people::FaceDetector Class Reference

List of all members.

Classes

struct  NullDeleter
struct  RestampedPositionMeasurement

Public Types

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
ApproximateDepthPolicy
typedef
message_filters::Synchronizer
< ApproximateDepthPolicy
ApproximateDepthSync
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
stereo_msgs::DisparityImage,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
ApproximateDispPolicy
typedef
message_filters::Synchronizer
< ApproximateDispPolicy
ApproximateDispSync
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
ExactDepthPolicy
typedef
message_filters::Synchronizer
< ExactDepthPolicy
ExactDepthSync
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::Image,
stereo_msgs::DisparityImage,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
ExactDispPolicy
typedef
message_filters::Synchronizer
< ExactDispPolicy
ExactDispSync

Public Member Functions

 FaceDetector (std::string name)
void goalCB ()
void imageCBAllDepth (const sensor_msgs::Image::ConstPtr &image, const sensor_msgs::Image::ConstPtr &depth_image, const sensor_msgs::CameraInfo::ConstPtr &c1_info, const sensor_msgs::CameraInfo::ConstPtr &c2_info)
 Image callback for synced messages.
void imageCBAllDisp (const sensor_msgs::Image::ConstPtr &image, const stereo_msgs::DisparityImage::ConstPtr &disp_image, const sensor_msgs::CameraInfo::ConstPtr &c1_info, const sensor_msgs::CameraInfo::ConstPtr &c2_info)
 Image callback for synced messages.
void posCallback (const people_msgs::PositionMeasurementConstPtr &pos_ptr)
 Position message callback.
void preemptCB ()
 ~FaceDetector ()

Public Attributes

boost::shared_ptr
< ApproximateDepthSync
approximate_depth_sync_
boost::shared_ptr
< ApproximateDispSync
approximate_disp_sync_
actionlib::SimpleActionServer
< face_detector::FaceDetectorAction
as_
const double BIGDIST_M
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
c1_info_sub_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
c2_info_sub_
image_geometry::StereoCameraModel cam_model_
ros::Publisher cloud_pub_
cv::Mat cv_image_out_
boost::mutex cv_mutex_
image_transport::SubscriberFilter depth_image_sub_
boost::mutex dimage_mutex_
message_filters::Subscriber
< stereo_msgs::DisparityImage > 
disp_image_sub_
bool do_continuous_
bool do_display_
bool do_publish_unknown_
boost::shared_ptr< ExactDepthSyncexact_depth_sync_
boost::shared_ptr< ExactDispSyncexact_disp_sync_
bool external_init_
Facesfaces_
face_detector::FaceDetectorFeedback feedback_
string haar_filename_
image_transport::SubscriberFilter image_sub_
image_transport::ImageTransport it_
boost::mutex limage_mutex_
string name_
ros::NodeHandle nh_
map< string,
RestampedPositionMeasurement
pos_list_
boost::mutex pos_mutex_
ros::Publisher pos_pub_
ros::Subscriber pos_sub_
bool quit_
double reliability_
face_detector::FaceDetectorResult result_
tf::TransformListener tf_
bool use_depth_

Private Member Functions

void displayFacesOnImage (vector< Box2D3D > faces_vector)
void matchAndDisplay (vector< Box2D3D > faces_vector, std_msgs::Header header)

Detailed Description

FaceDetector - A wrapper around OpenCV's face detection, plus some usage of depth from stereo to restrict the results based on plausible face size.

Definition at line 82 of file face_detection.cpp.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> people::FaceDetector::ApproximateDepthPolicy

Sync policy for approx time with depth.

Definition at line 108 of file face_detection.cpp.

Definition at line 110 of file face_detection.cpp.

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> people::FaceDetector::ApproximateDispPolicy

Sync policy for approx time with disparity.

Definition at line 100 of file face_detection.cpp.

Definition at line 102 of file face_detection.cpp.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> people::FaceDetector::ExactDepthPolicy

Sync policy for exact time with depth.

Definition at line 107 of file face_detection.cpp.

Definition at line 109 of file face_detection.cpp.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> people::FaceDetector::ExactDispPolicy

Sync policy for exact time with disparity.

Definition at line 99 of file face_detection.cpp.

Definition at line 101 of file face_detection.cpp.


Constructor & Destructor Documentation

people::FaceDetector::FaceDetector ( std::string  name) [inline]

Definition at line 163 of file face_detection.cpp.

Definition at line 284 of file face_detection.cpp.


Member Function Documentation

void people::FaceDetector::displayFacesOnImage ( vector< Box2D3D faces_vector) [inline, private]

Definition at line 579 of file face_detection.cpp.

void people::FaceDetector::goalCB ( ) [inline]

Definition at line 296 of file face_detection.cpp.

void people::FaceDetector::imageCBAllDepth ( const sensor_msgs::Image::ConstPtr &  image,
const sensor_msgs::Image::ConstPtr &  depth_image,
const sensor_msgs::CameraInfo::ConstPtr &  c1_info,
const sensor_msgs::CameraInfo::ConstPtr &  c2_info 
) [inline]

Image callback for synced messages.

For each new image: convert it to OpenCV format, perform face detection using OpenCV's haar filter cascade classifier, and (if requested) draw rectangles around the found faces. Can also compute which faces are associated (by proximity, currently) with faces it already has in its list of people.

Definition at line 345 of file face_detection.cpp.

void people::FaceDetector::imageCBAllDisp ( const sensor_msgs::Image::ConstPtr &  image,
const stereo_msgs::DisparityImage::ConstPtr &  disp_image,
const sensor_msgs::CameraInfo::ConstPtr &  c1_info,
const sensor_msgs::CameraInfo::ConstPtr &  c2_info 
) [inline]

Image callback for synced messages.

For each new image: convert it to OpenCV format, perform face detection using OpenCV's haar filter cascade classifier, and (if requested) draw rectangles around the found faces. Can also compute which faces are associated (by proximity, currently) with faces it already has in its list of people.

Definition at line 390 of file face_detection.cpp.

void people::FaceDetector::matchAndDisplay ( vector< Box2D3D faces_vector,
std_msgs::Header  header 
) [inline, private]

Definition at line 431 of file face_detection.cpp.

Position message callback.

When hooked into the person tracking filter, this callback will listen to messages from the filter with a person id and 3D position and adjust the person's face position accordingly.

Definition at line 311 of file face_detection.cpp.

Definition at line 300 of file face_detection.cpp.


Member Data Documentation

Definition at line 112 of file face_detection.cpp.

Definition at line 104 of file face_detection.cpp.

Definition at line 115 of file face_detection.cpp.

Definition at line 85 of file face_detection.cpp.

Left/rgb camera info msg.

Definition at line 95 of file face_detection.cpp.

Right/depth camera info msg.

Definition at line 96 of file face_detection.cpp.

ROS->OpenCV image_geometry conversion.

Definition at line 138 of file face_detection.cpp.

Definition at line 129 of file face_detection.cpp.

Display image.

Definition at line 134 of file face_detection.cpp.

Definition at line 157 of file face_detection.cpp.

Definition at line 93 of file face_detection.cpp.

Definition at line 157 of file face_detection.cpp.

Depth image msg. Disparity image msg.

Definition at line 94 of file face_detection.cpp.

True = run as a normal node, searching for faces continuously, False = run as an action, wait for action call to start detection.

Definition at line 159 of file face_detection.cpp.

True/false display images with bounding boxes locally.

Definition at line 133 of file face_detection.cpp.

Publish faces even if they have unknown depth/size. Will just use the image x,y in the pos field of the published position_measurement.

Definition at line 161 of file face_detection.cpp.

Definition at line 111 of file face_detection.cpp.

Definition at line 103 of file face_detection.cpp.

Definition at line 122 of file face_detection.cpp.

List of faces and associated fcns.

Definition at line 141 of file face_detection.cpp.

Definition at line 116 of file face_detection.cpp.

Training file for the haar cascade classifier.

Definition at line 143 of file face_detection.cpp.

Left/rgb image msg.

Definition at line 92 of file face_detection.cpp.

Definition at line 91 of file face_detection.cpp.

Definition at line 157 of file face_detection.cpp.

Name of the detector. Ie frontalface, profileface. These will be the names in the published face location msgs.

Definition at line 142 of file face_detection.cpp.

Definition at line 88 of file face_detection.cpp.

Queue of updated face positions from the filter.

Definition at line 151 of file face_detection.cpp.

Definition at line 157 of file face_detection.cpp.

Definition at line 130 of file face_detection.cpp.

Definition at line 121 of file face_detection.cpp.

Definition at line 153 of file face_detection.cpp.

Reliability of the predictions. This should depend on the training file used.

Definition at line 144 of file face_detection.cpp.

Definition at line 117 of file face_detection.cpp.

Definition at line 155 of file face_detection.cpp.

True/false use depth information.

Definition at line 137 of file face_detection.cpp.


The documentation for this class was generated from the following file:


face_detector
Author(s): Caroline Pantofaru
autogenerated on Thu Jan 2 2014 11:35:06