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

#include <people_detection_display_node.h>

List of all members.

Public Member Functions

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.
void inputCallback (const cob_perception_msgs::DetectionArray::ConstPtr &face_recognition_msg, const cob_perception_msgs::ColorDepthImageArray::ConstPtr &face_detection_msg, const sensor_msgs::Image::ConstPtr &colorimage_msg)
 checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive
 PeopleDetectionDisplayNode (ros::NodeHandle nh)
 ~PeopleDetectionDisplayNode ()

Protected Attributes

image_transport::SubscriberFilter colorimage_sub_
 Color camera image topic.
bool display_
 if on, several debug outputs are activated
bool display_timing_
message_filters::Subscriber
< cob_perception_msgs::ColorDepthImageArray > 
face_detection_subscriber_
 receives the face messages from the face detector
message_filters::Subscriber
< cob_perception_msgs::DetectionArray > 
face_recognition_subscriber_
 receives the face messages from the detection tracker
image_transport::ImageTransportit_
ros::NodeHandle node_handle_
 ROS node handle.
image_transport::Publisher people_detection_image_pub_
 topic for publishing the image containing the people positions
message_filters::Synchronizer
< message_filters::sync_policies::ApproximateTime
< cob_perception_msgs::DetectionArray,
cob_perception_msgs::ColorDepthImageArray,
sensor_msgs::Image > > * 
sync_input_3_

Detailed Description

Definition at line 104 of file people_detection_display_node.h.


Constructor & Destructor Documentation

Definition at line 70 of file people_detection_display_node.cpp.

Definition at line 105 of file people_detection_display_node.cpp.


Member Function Documentation

unsigned long PeopleDetectionDisplayNode::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.

Definition at line 114 of file people_detection_display_node.cpp.

void PeopleDetectionDisplayNode::inputCallback ( const cob_perception_msgs::DetectionArray::ConstPtr &  face_recognition_msg,
const cob_perception_msgs::ColorDepthImageArray::ConstPtr &  face_detection_msg,
const sensor_msgs::Image::ConstPtr &  colorimage_msg 
)

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

Definition at line 131 of file people_detection_display_node.cpp.


Member Data Documentation

Color camera image topic.

Definition at line 111 of file people_detection_display_node.h.

if on, several debug outputs are activated

Definition at line 124 of file people_detection_display_node.h.

Definition at line 125 of file people_detection_display_node.h.

receives the face messages from the face detector

Definition at line 116 of file people_detection_display_node.h.

receives the face messages from the detection tracker

Definition at line 117 of file people_detection_display_node.h.

Definition at line 110 of file people_detection_display_node.h.

ROS node handle.

Definition at line 121 of file people_detection_display_node.h.

topic for publishing the image containing the people positions

Definition at line 119 of file people_detection_display_node.h.

message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<cob_perception_msgs::DetectionArray, cob_perception_msgs::ColorDepthImageArray, sensor_msgs::Image> >* ipa_PeopleDetector::PeopleDetectionDisplayNode::sync_input_3_ [protected]

Definition at line 113 of file people_detection_display_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