Public Member Functions | |
double | abs (double x) |
CobPeopleDetectionNodelet () | |
double | computeFacePositionDistance (const cob_perception_msgs::Detection &previous_detection, const cob_perception_msgs::Detection ¤t_detection) |
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 | copyDetection (const cob_perception_msgs::Detection &src, cob_perception_msgs::Detection &dest, bool update=false, unsigned int updateIndex=UINT_MAX) |
bool | detectPeopleCallback (cob_people_detection::DetectPeople::Request &req, cob_people_detection::DetectPeople::Response &res) |
void | inputCallback (const cob_perception_msgs::DetectionArray::ConstPtr &face_position_msg_in, const sensor_msgs::Image::ConstPtr &people_segmentation_image_msg, const sensor_msgs::Image::ConstPtr &color_image_msg) |
checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive | |
void | onInit () |
Nodelet init function. | |
unsigned long | prepareFacePositionMessage (cob_perception_msgs::DetectionArray &face_position_msg_out) |
unsigned long | removeMultipleInstancesOfLabel () |
~CobPeopleDetectionNodelet () | |
Protected Attributes | |
image_transport::SubscriberFilter | color_image_sub_ |
Color camera image topic. | |
bool | display_ |
if on, several debug outputs are activated | |
double | face_identification_score_decay_rate_ |
face identification score decay rate (0 < x < 1), i.e. the score for each label at a certain detection location is multiplied by this factor | |
std::vector< std::map < std::string, double > > | face_identification_votes_ |
collects votes for all names (map index) ever assigned to each detection (vector index) in face_position_accumulator_ | |
std::vector < cob_perception_msgs::Detection > | face_position_accumulator_ |
accumulates face positions over time | |
boost::timed_mutex | face_position_accumulator_mutex_ |
secures write and read operations to face_position_accumulator_ | |
ros::Publisher | face_position_publisher_ |
publisher for the positions of the detected faces | |
message_filters::Subscriber < cob_perception_msgs::DetectionArray > | face_position_subscriber_ |
receives the face messages from the face detector | |
double | face_redetection_time_ |
timespan during which a face is preserved in the list of tracked faces although it is currently not visible | |
bool | fall_back_to_unknown_identification_ |
if this is true, the unknown label will be assigned for the identification of a person if it has the highest score, otherwise, the last detection of a name will display as label even if there has been a detection of Unknown recently for that face | |
image_transport::ImageTransport * | it_ |
double | min_face_identification_score_to_publish_ |
minimum face identification score to publish (0 <= x < max_score), i.e. this score must be exceeded by a label at a detection location before the person detection is published (higher values increase robustness against short misdetections, but consider the maximum possible score max_score w.r.t. the face_identification_score_decay_rate: new_score = (old_score+1)*face_identification_score_decay_rate --> max_score = face_identification_score_decay_rate/(1-face_identification_score_decay_rate)) | |
double | min_segmented_people_ratio_color_ |
the minimum area inside the face rectangle found in the color image that has to be covered with positive people segmentation results (from openni_tracker) | |
double | min_segmented_people_ratio_range_ |
the minimum area inside the face rectangle found in the range image that has to be covered with positive people segmentation results (from openni_tracker) | |
ros::NodeHandle | node_handle_ |
ROS node handle. | |
image_transport::Publisher | people_detection_image_pub_ |
topic for publishing the image containing the people positions | |
image_transport::SubscriberFilter | people_segmentation_image_sub_ |
Color camera image topic. | |
ros::ServiceServer | service_server_detect_people_ |
Service server to request people detection. | |
message_filters::Synchronizer < message_filters::sync_policies::ApproximateTime < cob_perception_msgs::DetectionArray, sensor_msgs::Image > > * | sync_input_2_ |
message_filters::Synchronizer < message_filters::sync_policies::ApproximateTime < cob_perception_msgs::DetectionArray, sensor_msgs::Image, sensor_msgs::Image > > * | sync_input_3_ |
double | tracking_range_m_ |
maximum tracking manhattan distance for a face (in meters), i.e. a face can move this distance between two images and can still be tracked | |
bool | use_people_segmentation_ |
enables the combination of face detections with the openni people segmentation |
Definition at line 114 of file people_detection.cpp.
Definition at line 149 of file people_detection.cpp.
Definition at line 156 of file people_detection.cpp.
double ipa_PeopleDetector::CobPeopleDetectionNodelet::abs | ( | double | x | ) | [inline] |
Definition at line 339 of file people_detection.cpp.
double ipa_PeopleDetector::CobPeopleDetectionNodelet::computeFacePositionDistance | ( | const cob_perception_msgs::Detection & | previous_detection, |
const cob_perception_msgs::Detection & | current_detection | ||
) | [inline] |
Computes the Euclidian distance of a recent faces detection to a current face detection. If the current face detection is outside the neighborhood of the previous detection, DBL_MAX is returned.
Definition at line 347 of file people_detection.cpp.
unsigned long ipa_PeopleDetector::CobPeopleDetectionNodelet::convertColorImageMessageToMat | ( | const sensor_msgs::Image::ConstPtr & | image_msg, |
cv_bridge::CvImageConstPtr & | image_ptr, | ||
cv::Mat & | image | ||
) | [inline] |
Converts a color image message to cv::Mat format.
Definition at line 246 of file people_detection.cpp.
unsigned long ipa_PeopleDetector::CobPeopleDetectionNodelet::copyDetection | ( | const cob_perception_msgs::Detection & | src, |
cob_perception_msgs::Detection & | dest, | ||
bool | update = false , |
||
unsigned int | updateIndex = UINT_MAX |
||
) | [inline] |
Copies the data from src to dest.
src | The new data which shall be copied into dest |
dst | The new data src is copied into dest |
update | If update is true, dest must contain the data which shall be updated |
updateIndex | The index in face_identification_votes_ corresponding to the previous detection dest. Only necessary if update is true. |
Definition at line 267 of file people_detection.cpp.
bool ipa_PeopleDetector::CobPeopleDetectionNodelet::detectPeopleCallback | ( | cob_people_detection::DetectPeople::Request & | req, |
cob_people_detection::DetectPeople::Response & | res | ||
) | [inline] |
Definition at line 686 of file people_detection.cpp.
void ipa_PeopleDetector::CobPeopleDetectionNodelet::inputCallback | ( | const cob_perception_msgs::DetectionArray::ConstPtr & | face_position_msg_in, |
const sensor_msgs::Image::ConstPtr & | people_segmentation_image_msg, | ||
const sensor_msgs::Image::ConstPtr & | color_image_msg | ||
) | [inline] |
checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive
Definition at line 440 of file people_detection.cpp.
void ipa_PeopleDetector::CobPeopleDetectionNodelet::onInit | ( | ) | [inline, virtual] |
Nodelet init function.
Implements nodelet::Nodelet.
Definition at line 167 of file people_detection.cpp.
unsigned long ipa_PeopleDetector::CobPeopleDetectionNodelet::prepareFacePositionMessage | ( | cob_perception_msgs::DetectionArray & | face_position_msg_out | ) | [inline] |
Definition at line 408 of file people_detection.cpp.
unsigned long ipa_PeopleDetector::CobPeopleDetectionNodelet::removeMultipleInstancesOfLabel | ( | ) | [inline] |
Removes multiple instances of a label by renaming the detections with lower score to Unknown.
Definition at line 370 of file people_detection.cpp.
image_transport::SubscriberFilter ipa_PeopleDetector::CobPeopleDetectionNodelet::color_image_sub_ [protected] |
Color camera image topic.
Definition at line 120 of file people_detection.cpp.
bool ipa_PeopleDetector::CobPeopleDetectionNodelet::display_ [protected] |
if on, several debug outputs are activated
Definition at line 137 of file people_detection.cpp.
double ipa_PeopleDetector::CobPeopleDetectionNodelet::face_identification_score_decay_rate_ [protected] |
face identification score decay rate (0 < x < 1), i.e. the score for each label at a certain detection location is multiplied by this factor
Definition at line 143 of file people_detection.cpp.
std::vector<std::map<std::string, double> > ipa_PeopleDetector::CobPeopleDetectionNodelet::face_identification_votes_ [protected] |
collects votes for all names (map index) ever assigned to each detection (vector index) in face_position_accumulator_
Definition at line 134 of file people_detection.cpp.
std::vector<cob_perception_msgs::Detection> ipa_PeopleDetector::CobPeopleDetectionNodelet::face_position_accumulator_ [protected] |
accumulates face positions over time
Definition at line 132 of file people_detection.cpp.
boost::timed_mutex ipa_PeopleDetector::CobPeopleDetectionNodelet::face_position_accumulator_mutex_ [protected] |
secures write and read operations to face_position_accumulator_
Definition at line 133 of file people_detection.cpp.
publisher for the positions of the detected faces
Definition at line 125 of file people_detection.cpp.
message_filters::Subscriber<cob_perception_msgs::DetectionArray> ipa_PeopleDetector::CobPeopleDetectionNodelet::face_position_subscriber_ [protected] |
receives the face messages from the face detector
Definition at line 124 of file people_detection.cpp.
double ipa_PeopleDetector::CobPeopleDetectionNodelet::face_redetection_time_ [protected] |
timespan during which a face is preserved in the list of tracked faces although it is currently not visible
Definition at line 139 of file people_detection.cpp.
bool ipa_PeopleDetector::CobPeopleDetectionNodelet::fall_back_to_unknown_identification_ [protected] |
if this is true, the unknown label will be assigned for the identification of a person if it has the highest score, otherwise, the last detection of a name will display as label even if there has been a detection of Unknown recently for that face
Definition at line 145 of file people_detection.cpp.
Definition at line 118 of file people_detection.cpp.
double ipa_PeopleDetector::CobPeopleDetectionNodelet::min_face_identification_score_to_publish_ [protected] |
minimum face identification score to publish (0 <= x < max_score), i.e. this score must be exceeded by a label at a detection location before the person detection is published (higher values increase robustness against short misdetections, but consider the maximum possible score max_score w.r.t. the face_identification_score_decay_rate: new_score = (old_score+1)*face_identification_score_decay_rate --> max_score = face_identification_score_decay_rate/(1-face_identification_score_decay_rate))
Definition at line 144 of file people_detection.cpp.
the minimum area inside the face rectangle found in the color image that has to be covered with positive people segmentation results (from openni_tracker)
Definition at line 140 of file people_detection.cpp.
the minimum area inside the face rectangle found in the range image that has to be covered with positive people segmentation results (from openni_tracker)
Definition at line 141 of file people_detection.cpp.
ROS node handle.
Definition at line 130 of file people_detection.cpp.
image_transport::Publisher ipa_PeopleDetector::CobPeopleDetectionNodelet::people_detection_image_pub_ [protected] |
topic for publishing the image containing the people positions
Definition at line 126 of file people_detection.cpp.
image_transport::SubscriberFilter ipa_PeopleDetector::CobPeopleDetectionNodelet::people_segmentation_image_sub_ [protected] |
Color camera image topic.
Definition at line 119 of file people_detection.cpp.
ros::ServiceServer ipa_PeopleDetector::CobPeopleDetectionNodelet::service_server_detect_people_ [protected] |
Service server to request people detection.
Definition at line 127 of file people_detection.cpp.
message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<cob_perception_msgs::DetectionArray, sensor_msgs::Image> >* ipa_PeopleDetector::CobPeopleDetectionNodelet::sync_input_2_ [protected] |
Definition at line 121 of file people_detection.cpp.
message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<cob_perception_msgs::DetectionArray, sensor_msgs::Image, sensor_msgs::Image> >* ipa_PeopleDetector::CobPeopleDetectionNodelet::sync_input_3_ [protected] |
Definition at line 123 of file people_detection.cpp.
double ipa_PeopleDetector::CobPeopleDetectionNodelet::tracking_range_m_ [protected] |
maximum tracking manhattan distance for a face (in meters), i.e. a face can move this distance between two images and can still be tracked
Definition at line 142 of file people_detection.cpp.
enables the combination of face detections with the openni people segmentation
Definition at line 138 of file people_detection.cpp.