$search

people::FaceDetectorColor Class Reference

Inheritance diagram for people::FaceDetectorColor:
Inheritance graph
[legend]

List of all members.

Classes

struct  NullDeleter
struct  RestampedPositionMeasurement

Public Member Functions

 FaceDetectorColor ()
void goalCB ()
void imageCBAll (const sensor_msgs::Image::ConstPtr &limage, const stereo_msgs::DisparityImage::ConstPtr &dimage, const sensor_msgs::CameraInfo::ConstPtr &lcinfo, const sensor_msgs::CameraInfo::ConstPtr &rcinfo, const sensor_msgs::PointCloud2::ConstPtr &depth_cloud_msg)
 Image callback for synced messages.
void onInit ()
void posCallback (const cob_people_detection::PositionMeasurementConstPtr &pos_ptr)
 Position message callback.
void preemptCB ()
 ~FaceDetectorColor ()

Public Attributes

actionlib::SimpleActionServer
< cob_people_detection::FaceDetectorAction > * 
as_
const double BIGDIST_M
image_geometry::StereoCameraModel cam_model_
ros::Publisher cloud_pub_
cv::Mat cv_image_out_
boost::mutex cv_mutex_
string data_source_mode_
sensor_msgs::CvBridge dbridge_
message_filters::Subscriber
< sensor_msgs::PointCloud2
depth_cloud_sub_
boost::mutex dimage_mutex_
message_filters::Subscriber
< stereo_msgs::DisparityImage
dimage_sub_
bool do_continuous_
string do_display_
bool do_display_disparity_or_depth_
bool do_publish_unknown_
bool external_init_
Facesfaces_
cob_people_detection::FaceDetectorFeedback feedback_
string haar_filename_
image_transport::ImageTransport it_
sensor_msgs::CvBridge lbridge_
message_filters::Subscriber
< sensor_msgs::CameraInfo
lcinfo_sub_
boost::mutex limage_mutex_
image_transport::SubscriberFilter limage_sub_
string name_
ros::NodeHandle nh_
std::string node_name_
map< string,
RestampedPositionMeasurement
pos_list_
boost::mutex pos_mutex_
ros::Publisher pos_pub_
ros::Subscriber pos_sub_
bool quit_
message_filters::Subscriber
< sensor_msgs::CameraInfo
rcinfo_sub_
double reliability_
cob_people_detection::FaceDetectorResult result_
message_filters::Synchronizer
< message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::PointCloud2 > > 
sync_pointcloud_nodisp_
message_filters::Synchronizer
< message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
stereo_msgs::DisparityImage,
sensor_msgs::PointCloud2 > > 
sync_pointcloud_showdisp_
message_filters::TimeSynchronizer
< sensor_msgs::Image,
stereo_msgs::DisparityImage,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo
sync_stereo_
tf::TransformListener tf_
bool use_depth_

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 87 of file color_face_detection.cpp.


Constructor & Destructor Documentation

people::FaceDetectorColor::FaceDetectorColor (  )  [inline]

Definition at line 273 of file color_face_detection.cpp.

people::FaceDetectorColor::~FaceDetectorColor (  )  [inline]

Definition at line 285 of file color_face_detection.cpp.


Member Function Documentation

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

Definition at line 300 of file color_face_detection.cpp.

void people::FaceDetectorColor::imageCBAll ( const sensor_msgs::Image::ConstPtr limage,
const stereo_msgs::DisparityImage::ConstPtr dimage,
const sensor_msgs::CameraInfo::ConstPtr lcinfo,
const sensor_msgs::CameraInfo::ConstPtr rcinfo,
const sensor_msgs::PointCloud2::ConstPtr depth_cloud_msg 
) [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 354 of file color_face_detection.cpp.

void people::FaceDetectorColor::onInit (  )  [inline, virtual]

Implements nodelet::Nodelet.

Definition at line 166 of file color_face_detection.cpp.

void people::FaceDetectorColor::posCallback ( const cob_people_detection::PositionMeasurementConstPtr &  pos_ptr  )  [inline]

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 317 of file color_face_detection.cpp.

void people::FaceDetectorColor::preemptCB (  )  [inline]

Definition at line 305 of file color_face_detection.cpp.


Member Data Documentation

actionlib::SimpleActionServer<cob_people_detection::FaceDetectorAction>* people::FaceDetectorColor::as_

Definition at line 114 of file color_face_detection.cpp.

Definition at line 90 of file color_face_detection.cpp.

ROS->OpenCV image_geometry conversion.

Definition at line 141 of file color_face_detection.cpp.

Definition at line 128 of file color_face_detection.cpp.

Display image.

Definition at line 133 of file color_face_detection.cpp.

Definition at line 160 of file color_face_detection.cpp.

"stereo" or "pointcloud"

Definition at line 137 of file color_face_detection.cpp.

ROS->OpenCV bridge for the disparity image.

Definition at line 103 of file color_face_detection.cpp.

PointCloud2 input from ROS message

Definition at line 104 of file color_face_detection.cpp.

Definition at line 160 of file color_face_detection.cpp.

Disparity image msg.

Definition at line 99 of file color_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 162 of file color_face_detection.cpp.

Type of display, none/local

Definition at line 132 of file color_face_detection.cpp.

Displays the disparity image (in case of stereo camera sensor) or the depth image (if available besides the point cloud)

Definition at line 134 of file color_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 164 of file color_face_detection.cpp.

Definition at line 121 of file color_face_detection.cpp.

List of faces and associated fcns.

Definition at line 144 of file color_face_detection.cpp.

cob_people_detection::FaceDetectorFeedback people::FaceDetectorColor::feedback_

Definition at line 115 of file color_face_detection.cpp.

Training file for the haar cascade classifier.

Definition at line 146 of file color_face_detection.cpp.

Definition at line 97 of file color_face_detection.cpp.

ROS->OpenCV bridge for the left image.

Definition at line 102 of file color_face_detection.cpp.

Left camera info msg.

Definition at line 100 of file color_face_detection.cpp.

Definition at line 160 of file color_face_detection.cpp.

Left image msg.

Definition at line 98 of file color_face_detection.cpp.

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

Definition at line 145 of file color_face_detection.cpp.

Reimplemented from nodelet::Nodelet.

Definition at line 93 of file color_face_detection.cpp.

Definition at line 94 of file color_face_detection.cpp.

Queue of updated face positions from the filter.

Definition at line 154 of file color_face_detection.cpp.

Definition at line 160 of file color_face_detection.cpp.

Definition at line 129 of file color_face_detection.cpp.

Definition at line 120 of file color_face_detection.cpp.

Definition at line 156 of file color_face_detection.cpp.

Right camera info msg.

Definition at line 101 of file color_face_detection.cpp.

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

Definition at line 147 of file color_face_detection.cpp.

cob_people_detection::FaceDetectorResult people::FaceDetectorColor::result_

Definition at line 116 of file color_face_detection.cpp.

Pointcloud synchronizer without disparity display.

Definition at line 110 of file color_face_detection.cpp.

Pointcloud synchronizer with disparity display.

Definition at line 109 of file color_face_detection.cpp.

Stereo topic synchronizer.

Definition at line 107 of file color_face_detection.cpp.

Definition at line 158 of file color_face_detection.cpp.

True/false use depth information.

Definition at line 140 of file color_face_detection.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


cob_people_detection
Author(s): Richard Bormann
autogenerated on Tue Mar 5 11:50:14 2013