#include <face_normalizer_node.h>
Public Member Functions | |
FaceNormalizerNode (ros::NodeHandle nh) | |
~FaceNormalizerNode (void) | |
Destructor. | |
Protected Member Functions | |
void | facePositionsCallback (const cob_perception_msgs::ColorDepthImageArray::ConstPtr &face_positions) |
Callback for incoming head detections. | |
Protected Attributes | |
std::string | debug_directory_ |
path to the classifier model | |
FaceNormalizer | face_normalizer_ |
implementation of the face recognizer | |
ros::Subscriber | face_position_subscriber_ |
subscribes to the positions of detected face regions | |
ros::NodeHandle | node_handle_ |
ros::Publisher | norm_face_publisher_ |
publisher for normalized faces |
Definition at line 88 of file face_normalizer_node.h.
Destructor.
Definition at line 97 of file face_normalizer_node.cpp.
void FaceNormalizerNode::facePositionsCallback | ( | const cob_perception_msgs::ColorDepthImageArray::ConstPtr & | face_positions | ) | [protected] |
Callback for incoming head detections.
Definition at line 101 of file face_normalizer_node.cpp.
std::string ipa_PeopleDetector::FaceNormalizerNode::debug_directory_ [protected] |
path to the classifier model
Definition at line 113 of file face_normalizer_node.h.
implementation of the face recognizer
Definition at line 109 of file face_normalizer_node.h.
subscribes to the positions of detected face regions
Definition at line 105 of file face_normalizer_node.h.
Definition at line 103 of file face_normalizer_node.h.
publisher for normalized faces
Definition at line 107 of file face_normalizer_node.h.