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

#include <head_detector_node.h>

List of all members.

Public Member Functions

 HeadDetectorNode (ros::NodeHandle nh)
 ~HeadDetectorNode (void)
 Destructor.

Protected Member Functions

unsigned long convertPclMessageToMat (const sensor_msgs::PointCloud2::ConstPtr &pointlcoud, cv::Mat &depth_image, cv::Mat &color_image)
void pointcloud_callback (const sensor_msgs::PointCloud2::ConstPtr &pointcloud)
 Callback for incoming point clouds.

Protected Attributes

std::string data_directory_
 path to the classifier model
bool display_timing_
bool fill_unassigned_depth_values_
 fills the unassigned depth values in the depth image, must be true for a kinect sensor
HeadDetector head_detector_
 implementation of the head detector
ros::Publisher head_position_publisher_
 publisher for the positions of the detected heads
ros::NodeHandle node_handle_
ros::Subscriber pointcloud_sub_
 subscribes to a colored point cloud

Detailed Description

Definition at line 79 of file head_detector_node.h.


Constructor & Destructor Documentation

Constructor

Parameters:
nhROS node handle

Definition at line 82 of file head_detector_node.cpp.

Destructor.

Definition at line 120 of file head_detector_node.cpp.


Member Function Documentation

unsigned long HeadDetectorNode::convertPclMessageToMat ( const sensor_msgs::PointCloud2::ConstPtr &  pointlcoud,
cv::Mat &  depth_image,
cv::Mat &  color_image 
) [protected]

Definition at line 180 of file head_detector_node.cpp.

void HeadDetectorNode::pointcloud_callback ( const sensor_msgs::PointCloud2::ConstPtr &  pointcloud) [protected]

Callback for incoming point clouds.

Definition at line 124 of file head_detector_node.cpp.


Member Data Documentation

path to the classifier model

Definition at line 105 of file head_detector_node.h.

Definition at line 107 of file head_detector_node.h.

fills the unassigned depth values in the depth image, must be true for a kinect sensor

Definition at line 106 of file head_detector_node.h.

implementation of the head detector

Definition at line 102 of file head_detector_node.h.

publisher for the positions of the detected heads

Definition at line 100 of file head_detector_node.h.

Definition at line 96 of file head_detector_node.h.

subscribes to a colored point cloud

Definition at line 98 of file head_detector_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