Public Member Functions | Protected Member Functions | Protected Attributes
ipa_PeopleDetector::FaceRecognizerNode Class Reference

#include <face_recognizer_node.h>

List of all members.

Public Member Functions

 FaceRecognizerNode (ros::NodeHandle nh)
 ~FaceRecognizerNode (void)
 Destructor.

Protected Member Functions

bool determine3DFaceCoordinates (cv::Mat &depth_image, int center2Dx, int center2Dy, geometry_msgs::Point &center3D, int search_radius)
void facePositionsCallback (const cob_perception_msgs::ColorDepthImageArray::ConstPtr &face_positions)
 Callback for incoming head detections.
void loadModelServerCallback (const cob_people_detection::loadModelGoalConstPtr &goal)
 Callback for load requests to load a new recognition model.

Protected Attributes

std::string classifier_directory_
 path to the face feature haarcascades
std::string data_directory_
 path to the classifier model
bool display_timing_
bool enable_face_recognition_
 this flag enables or disables the face recognition step
ros::Subscriber face_position_subscriber_
 subscribes to the positions of detected face regions
ros::Publisher face_recognition_publisher_
 publisher for the positions and labels of the detected faces
FaceRecognizer face_recognizer_
 implementation of the face recognizer
LoadModelServerload_model_server_
 Action server that handles load requests for a new recognition model.
ros::NodeHandle node_handle_

Detailed Description

Definition at line 91 of file face_recognizer_node.h.


Constructor & Destructor Documentation

Constructor

Parameters:
nhROS node handle

Definition at line 80 of file face_recognizer_node.cpp.

Destructor.

Definition at line 178 of file face_recognizer_node.cpp.


Member Function Documentation

bool FaceRecognizerNode::determine3DFaceCoordinates ( cv::Mat &  depth_image,
int  center2Dx,
int  center2Dy,
geometry_msgs::Point center3D,
int  search_radius 
) [protected]

Computes the 3D coordinate of a detected face.

Parameters:
depth_imageCoordinate image in format CV32FC3
center2DxImage x-coordinate of the center of the detected face
center2DyImage y-coordinate of the center of the detected face
center3D(x,y,z) coordinates of the face's center point
search_radiusRadius of pixel neighborhood which is searched for valid 3D coordinates.
Returns:
Indicates whether the found 3D coordinates are valid, i.e. if true, the 3D coordinates do not contain NaN values and are valid.

Definition at line 537 of file face_recognizer_node.cpp.

void FaceRecognizerNode::facePositionsCallback ( const cob_perception_msgs::ColorDepthImageArray::ConstPtr &  face_positions) [protected]

Callback for incoming head detections.

Definition at line 368 of file face_recognizer_node.cpp.

void FaceRecognizerNode::loadModelServerCallback ( const cob_people_detection::loadModelGoalConstPtr &  goal) [protected]

Callback for load requests to load a new recognition model.

Definition at line 566 of file face_recognizer_node.cpp.


Member Data Documentation

path to the face feature haarcascades

Definition at line 132 of file face_recognizer_node.h.

path to the classifier model

Definition at line 131 of file face_recognizer_node.h.

Definition at line 134 of file face_recognizer_node.h.

this flag enables or disables the face recognition step

Definition at line 133 of file face_recognizer_node.h.

subscribes to the positions of detected face regions

Definition at line 121 of file face_recognizer_node.h.

publisher for the positions and labels of the detected faces

Definition at line 123 of file face_recognizer_node.h.

implementation of the face recognizer

Definition at line 127 of file face_recognizer_node.h.

Action server that handles load requests for a new recognition model.

Definition at line 125 of file face_recognizer_node.h.

Definition at line 119 of file face_recognizer_node.h.


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


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Fri Aug 28 2015 10:24:13