detection_tracker_node.h
Go to the documentation of this file.
00001 
00060 #ifndef _DETECTION_TRACKER_
00061 #define _DETECTION_TRACKER_
00062 
00063 //##################
00064 //#### includes ####
00065 
00066 // standard includes
00067 //--
00068 
00069 // ROS includes
00070 #include <ros/ros.h>
00071 #include <ros/package.h>
00072 
00073 // ROS message includes
00074 #include <sensor_msgs/Image.h>
00075 //#include <sensor_msgs/PointCloud2.h>
00076 #include <cob_perception_msgs/DetectionArray.h>
00077 
00078 // services
00079 //#include <cob_people_detection/DetectPeople.h>
00080 
00081 // topics
00082 #include <message_filters/subscriber.h>
00083 #include <message_filters/synchronizer.h>
00084 #include <message_filters/sync_policies/approximate_time.h>
00085 #include <image_transport/image_transport.h>
00086 #include <image_transport/subscriber_filter.h>
00087 
00088 // opencv
00089 #include <opencv/cv.h>
00090 #include <opencv/highgui.h>
00091 #include <cv_bridge/cv_bridge.h>
00092 #include <sensor_msgs/image_encodings.h>
00093 
00094 // boost
00095 #include <boost/bind.hpp>
00096 #include <boost/thread/mutex.hpp>
00097 
00098 // external includes
00099 #include "cob_vision_utils/GlobalDefines.h"
00100 
00101 #include <sstream>
00102 #include <string>
00103 #include <vector>
00104 
00105 namespace ipa_PeopleDetector
00106 {
00107 
00108 class DetectionTrackerNode
00109 {
00110 protected:
00111         image_transport::ImageTransport* it_;
00112         image_transport::SubscriberFilter people_segmentation_image_sub_; 
00113 
00114         message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<cob_perception_msgs::DetectionArray, sensor_msgs::Image> >* sync_input_2_;
00115         message_filters::Subscriber<cob_perception_msgs::DetectionArray> face_position_subscriber_; 
00116         ros::Publisher face_position_publisher_; 
00117 
00118         ros::NodeHandle node_handle_; 
00119 
00120         std::vector<cob_perception_msgs::Detection> face_position_accumulator_; 
00121         boost::timed_mutex face_position_accumulator_mutex_; 
00122         std::vector<std::map<std::string, double> > face_identification_votes_; 
00123 
00124         // parameters
00125         bool debug_; 
00126         bool use_people_segmentation_; 
00127         double face_redetection_time_; 
00128         ros::Duration publish_currently_not_visible_detections_timespan_; 
00129         double min_segmented_people_ratio_face_; 
00130         double min_segmented_people_ratio_head_; 
00131         double tracking_range_m_; 
00132         double face_identification_score_decay_rate_; 
00133         double min_face_identification_score_to_publish_; 
00134         bool fall_back_to_unknown_identification_; 
00135         bool display_timing_;
00136 
00137         bool rosbag_mode_; 
00138 
00139 public:
00140 
00141         DetectionTrackerNode(ros::NodeHandle nh);
00142 
00143         ~DetectionTrackerNode();
00144 
00146         unsigned long convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& image_msg, cv_bridge::CvImageConstPtr& image_ptr, cv::Mat& image);
00147 
00154         unsigned long copyDetection(const cob_perception_msgs::Detection& src, cob_perception_msgs::Detection& dest, bool update = false,
00155                         unsigned int updateIndex = UINT_MAX);
00156 
00160         double computeFacePositionDistanceTrackingRange(const cob_perception_msgs::Detection& previous_detection, const cob_perception_msgs::Detection& current_detection);
00161 
00164         double computeFacePositionDistance(const cob_perception_msgs::Detection& previous_detection, const cob_perception_msgs::Detection& current_detection);
00165 
00168         unsigned long removeMultipleInstancesOfLabel();
00169 
00170         unsigned long prepareFacePositionMessage(cob_perception_msgs::DetectionArray& face_position_msg_out, ros::Time image_recording_time);
00171 
00173         void inputCallback(const cob_perception_msgs::DetectionArray::ConstPtr& face_position_msg_in, const sensor_msgs::Image::ConstPtr& people_segmentation_image_msg);
00174 
00175 };
00176 
00177 }
00178 ;
00179 
00180 #endif // _DETECTION_TRACKER_


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