Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
ipa_PeopleDetector::FaceCaptureNode Class Reference

#include <face_capture_node.h>

List of all members.

Public Member Functions

 FaceCaptureNode (ros::NodeHandle nh)
 ~FaceCaptureNode ()

Protected Types

enum  CaptureMode { MANUAL = 0, CONTINUOUS }
enum  UpdateMode { BY_INDEX = 1, BY_LABEL }

Protected Member Functions

void addDataServerCallback (const cob_people_detection::addDataGoalConstPtr &goal)
bool captureImageCallback (cob_people_detection::captureImage::Request &req, cob_people_detection::captureImage::Response &res)
unsigned long convertColorImageMessageToMat (const sensor_msgs::Image::ConstPtr &image_msg, cv_bridge::CvImageConstPtr &image_ptr, cv::Mat &image)
 Converts a color image message to cv::Mat format.
unsigned long convertDepthImageMessageToMat (const sensor_msgs::Image::ConstPtr &image_msg, cv_bridge::CvImageConstPtr &image_ptr, cv::Mat &image)
 Converts a depth image message to cv::Mat format.
void deleteDataServerCallback (const cob_people_detection::deleteDataGoalConstPtr &goal)
bool finishRecordingCallback (cob_people_detection::finishRecording::Request &req, cob_people_detection::finishRecording::Response &res)
void inputCallback (const cob_perception_msgs::ColorDepthImageArray::ConstPtr &face_detection_msg)
 checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive
void updateDataServerCallback (const cob_people_detection::updateDataGoalConstPtr &goal)

Protected Attributes

boost::mutex active_action_mutex_
 facilitates that only one action server can be active at the same time
AddDataServeradd_data_server_
 Action server that handles add data requests.
bool capture_image_
image_transport::SubscriberFilter color_image_sub_
 Color camera image topic.
std::string current_label_
 Label of currently captured images.
std::string data_directory_
 path to the classifier model
DeleteDataServerdelete_data_server_
 Action server that handles delete data requests.
std::vector< cv::Mat > face_depthmaps_
 Vector of face depthmaps.
message_filters::Subscriber
< cob_perception_msgs::ColorDepthImageArray > 
face_detection_subscriber_
 receives the face messages from the face detector
std::vector< cv::Mat > face_images_
 Vector of face images.
FaceRecognizer face_recognizer_trainer_
bool finish_image_capture_
image_transport::ImageTransportit_
ros::NodeHandle node_handle_
 ROS node handle.
int number_captured_images_
ros::ServiceServer service_server_capture_image_
 Service server that triggers an image recording.
ros::ServiceServer service_server_finish_recording_
 Service server that finishes image recording.
message_filters::Synchronizer
< message_filters::sync_policies::ApproximateTime
< cob_perception_msgs::ColorDepthImageArray,
sensor_msgs::Image > > * 
sync_input_2_
UpdateDataServerupdate_data_server_
 Action server that handles update data requests.

Detailed Description

Definition at line 116 of file face_capture_node.h.


Member Enumeration Documentation

Enumerator:
MANUAL 
CONTINUOUS 

Definition at line 133 of file face_capture_node.h.

Enumerator:
BY_INDEX 
BY_LABEL 

Definition at line 137 of file face_capture_node.h.


Constructor & Destructor Documentation

Definition at line 67 of file face_capture_node.cpp.

Definition at line 130 of file face_capture_node.cpp.


Member Function Documentation

void FaceCaptureNode::addDataServerCallback ( const cob_people_detection::addDataGoalConstPtr &  goal) [protected]

Definition at line 139 of file face_capture_node.cpp.

bool FaceCaptureNode::captureImageCallback ( cob_people_detection::captureImage::Request &  req,
cob_people_detection::captureImage::Response &  res 
) [protected]

Definition at line 310 of file face_capture_node.cpp.

unsigned long FaceCaptureNode::convertColorImageMessageToMat ( const sensor_msgs::Image::ConstPtr &  image_msg,
cv_bridge::CvImageConstPtr image_ptr,
cv::Mat &  image 
) [protected]

Converts a color image message to cv::Mat format.

Definition at line 277 of file face_capture_node.cpp.

unsigned long FaceCaptureNode::convertDepthImageMessageToMat ( const sensor_msgs::Image::ConstPtr &  image_msg,
cv_bridge::CvImageConstPtr image_ptr,
cv::Mat &  image 
) [protected]

Converts a depth image message to cv::Mat format.

Definition at line 294 of file face_capture_node.cpp.

void FaceCaptureNode::deleteDataServerCallback ( const cob_people_detection::deleteDataGoalConstPtr &  goal) [protected]

Definition at line 358 of file face_capture_node.cpp.

bool FaceCaptureNode::finishRecordingCallback ( cob_people_detection::finishRecording::Request &  req,
cob_people_detection::finishRecording::Response &  res 
) [protected]

Definition at line 320 of file face_capture_node.cpp.

void FaceCaptureNode::inputCallback ( const cob_perception_msgs::ColorDepthImageArray::ConstPtr &  face_detection_msg) [protected]

checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive

captures the images

Definition at line 216 of file face_capture_node.cpp.

void FaceCaptureNode::updateDataServerCallback ( const cob_people_detection::updateDataGoalConstPtr &  goal) [protected]

Definition at line 326 of file face_capture_node.cpp.


Member Data Documentation

facilitates that only one action server can be active at the same time

Definition at line 123 of file face_capture_node.h.

Action server that handles add data requests.

Definition at line 152 of file face_capture_node.h.

Definition at line 130 of file face_capture_node.h.

Color camera image topic.

Definition at line 149 of file face_capture_node.h.

Label of currently captured images.

Definition at line 129 of file face_capture_node.h.

path to the classifier model

Definition at line 161 of file face_capture_node.h.

Action server that handles delete data requests.

Definition at line 154 of file face_capture_node.h.

std::vector<cv::Mat> ipa_PeopleDetector::FaceCaptureNode::face_depthmaps_ [protected]

Vector of face depthmaps.

Definition at line 128 of file face_capture_node.h.

receives the face messages from the face detector

Definition at line 148 of file face_capture_node.h.

std::vector<cv::Mat> ipa_PeopleDetector::FaceCaptureNode::face_images_ [protected]

Vector of face images.

Definition at line 127 of file face_capture_node.h.

Definition at line 126 of file face_capture_node.h.

Definition at line 132 of file face_capture_node.h.

Definition at line 143 of file face_capture_node.h.

ROS node handle.

Definition at line 120 of file face_capture_node.h.

Definition at line 131 of file face_capture_node.h.

Service server that triggers an image recording.

Definition at line 157 of file face_capture_node.h.

Service server that finishes image recording.

Definition at line 158 of file face_capture_node.h.

Definition at line 147 of file face_capture_node.h.

Action server that handles update data requests.

Definition at line 153 of file face_capture_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