#include <head_detector_node.h>
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 |
Definition at line 79 of file head_detector_node.h.
HeadDetectorNode::~HeadDetectorNode | ( | void | ) |
Destructor.
Definition at line 120 of file head_detector_node.cpp.
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.
std::string ipa_PeopleDetector::HeadDetectorNode::data_directory_ [protected] |
path to the classifier model
Definition at line 105 of file head_detector_node.h.
bool ipa_PeopleDetector::HeadDetectorNode::display_timing_ [protected] |
Definition at line 107 of file head_detector_node.h.
bool ipa_PeopleDetector::HeadDetectorNode::fill_unassigned_depth_values_ [protected] |
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.