head_detector_node.h
Go to the documentation of this file.
00001 
00061 #ifndef __HEAD_DETECTOR_NODE_H__
00062 #define __HEAD_DETECTOR_NODE_H__
00063 
00064 #ifdef __LINUX__
00065 #include "cob_people_detection/head_detector.h"
00066 #else
00067 #endif
00068 
00069 // ROS includes
00070 #include <ros/ros.h>
00071 #include <ros/package.h>                // use as: directory_ = ros::package::getPath("cob_people_detection") + "/common/files/windows/";
00072 // ROS message includes
00073 #include <sensor_msgs/PointCloud2.h>
00074 #include <cob_perception_msgs/ColorDepthImageArray.h>
00075 
00076 namespace ipa_PeopleDetector
00077 {
00078 
00079 class HeadDetectorNode
00080 {
00081 public:
00082 
00085         HeadDetectorNode(ros::NodeHandle nh);
00086         ~HeadDetectorNode(void); 
00087 
00088 
00089 protected:
00090 
00092         void pointcloud_callback(const sensor_msgs::PointCloud2::ConstPtr& pointcloud);
00093 
00094         unsigned long convertPclMessageToMat(const sensor_msgs::PointCloud2::ConstPtr& pointlcoud, cv::Mat& depth_image, cv::Mat& color_image);
00095 
00096         ros::NodeHandle node_handle_;
00097 
00098         ros::Subscriber pointcloud_sub_; 
00099 
00100         ros::Publisher head_position_publisher_; 
00101 
00102         HeadDetector head_detector_; 
00103 
00104         // parameters
00105         std::string data_directory_; 
00106         bool fill_unassigned_depth_values_; 
00107         bool display_timing_;
00108 };
00109 
00110 } // end namespace
00111 
00112 #endif // __HEAD_DETECTOR_NODE_H__


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Fri Aug 28 2015 10:24:13