Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #ifndef COSTMAP_OBSERVATION_BUFFER_H_
00038 #define COSTMAP_OBSERVATION_BUFFER_H_
00039 
00040 #include <vector>
00041 #include <list>
00042 #include <string>
00043 #include <ros/time.h>
00044 #include <costmap_2d/observation.h>
00045 #include <tf/transform_listener.h>
00046 #include <tf/transform_datatypes.h>
00047 
00048 
00049 #include <pcl/point_cloud.h>
00050 #include <sensor_msgs/PointCloud2.h>
00051 
00052 
00053 #include <boost/thread.hpp>
00054 
00055 namespace costmap_2d {
00060   class ObservationBuffer {
00061     public:
00076       ObservationBuffer(std::string topic_name, double observation_keep_time, double expected_update_rate, 
00077           double min_obstacle_height, double max_obstacle_height, double obstacle_range, double raytrace_range,
00078           tf::TransformListener& tf, std::string global_frame, std::string sensor_frame, double tf_tolerance);
00079 
00083       ~ObservationBuffer();
00084 
00092       bool setGlobalFrame(const std::string new_global_frame);
00093 
00099       void bufferCloud(const sensor_msgs::PointCloud2& cloud);
00100 
00106       void bufferCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud);
00107 
00112       void getObservations(std::vector<Observation>& observations);
00113 
00118       bool isCurrent() const;
00119 
00123       inline void lock() { lock_.lock(); }
00124 
00128       inline void unlock() { lock_.unlock(); }
00129       
00133       void resetLastUpdated ();
00134 
00135     private:
00139       void purgeStaleObservations();
00140 
00141       tf::TransformListener& tf_;
00142       const ros::Duration observation_keep_time_;
00143       const ros::Duration expected_update_rate_;
00144       ros::Time last_updated_;
00145       std::string global_frame_;
00146       std::string sensor_frame_;
00147       std::list<Observation> observation_list_;
00148       std::string topic_name_;
00149       double min_obstacle_height_, max_obstacle_height_;
00150       boost::recursive_mutex lock_; 
00151       double obstacle_range_, raytrace_range_;
00152       double tf_tolerance_;
00153   };
00154 };
00155 #endif