#include <face_recognizer_node.h>
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 ¢er3D, 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 | |
LoadModelServer * | load_model_server_ |
Action server that handles load requests for a new recognition model. | |
ros::NodeHandle | node_handle_ |
Definition at line 91 of file face_recognizer_node.h.
Destructor.
Definition at line 178 of file face_recognizer_node.cpp.
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.
depth_image | Coordinate image in format CV32FC3 |
center2Dx | Image x-coordinate of the center of the detected face |
center2Dy | Image y-coordinate of the center of the detected face |
center3D | (x,y,z) coordinates of the face's center point |
search_radius | Radius of pixel neighborhood which is searched for valid 3D coordinates. |
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.
std::string ipa_PeopleDetector::FaceRecognizerNode::classifier_directory_ [protected] |
path to the face feature haarcascades
Definition at line 132 of file face_recognizer_node.h.
std::string ipa_PeopleDetector::FaceRecognizerNode::data_directory_ [protected] |
path to the classifier model
Definition at line 131 of file face_recognizer_node.h.
bool ipa_PeopleDetector::FaceRecognizerNode::display_timing_ [protected] |
Definition at line 134 of file face_recognizer_node.h.
bool ipa_PeopleDetector::FaceRecognizerNode::enable_face_recognition_ [protected] |
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.