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_2D_OBSERVATION_BUFFER_H_
00038 #define COSTMAP_2D_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
00056 {
00061 class ObservationBuffer
00062 {
00063 public:
00078 ObservationBuffer(std::string topic_name, double observation_keep_time, double expected_update_rate,
00079 double min_obstacle_height, double max_obstacle_height, double obstacle_range,
00080 double raytrace_range, tf::TransformListener& tf, std::string global_frame,
00081 std::string sensor_frame, double tf_tolerance);
00082
00086 ~ObservationBuffer();
00087
00095 bool setGlobalFrame(const std::string new_global_frame);
00096
00102 void bufferCloud(const sensor_msgs::PointCloud2& cloud);
00103
00109 void bufferCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud);
00110
00115 void getObservations(std::vector<Observation>& observations);
00116
00121 bool isCurrent() const;
00122
00126 inline void lock()
00127 {
00128 lock_.lock();
00129 }
00130
00134 inline void unlock()
00135 {
00136 lock_.unlock();
00137 }
00138
00142 void resetLastUpdated();
00143
00144 private:
00148 void purgeStaleObservations();
00149
00150 tf::TransformListener& tf_;
00151 const ros::Duration observation_keep_time_;
00152 const ros::Duration expected_update_rate_;
00153 ros::Time last_updated_;
00154 std::string global_frame_;
00155 std::string sensor_frame_;
00156 std::list<Observation> observation_list_;
00157 std::string topic_name_;
00158 double min_obstacle_height_, max_obstacle_height_;
00159 boost::recursive_mutex lock_;
00160 double obstacle_range_, raytrace_range_;
00161 double tf_tolerance_;
00162 };
00163 }
00164 #endif // COSTMAP_2D_OBSERVATION_BUFFER_H_
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15