Go to the documentation of this file.
   37 #ifndef COSTMAP_2D_OBSERVATION_BUFFER_H_ 
   38 #define COSTMAP_2D_OBSERVATION_BUFFER_H_ 
   47 #include <sensor_msgs/PointCloud2.h> 
   50 #include <boost/thread.hpp> 
   58 class ObservationBuffer
 
   75   ObservationBuffer(std::string topic_name, 
double observation_keep_time, 
double expected_update_rate,
 
   76                     double min_obstacle_height, 
double max_obstacle_height, 
double obstacle_range,
 
   77                     double raytrace_range, 
tf2_ros::Buffer& tf2_buffer, std::string global_frame,
 
   78                     std::string sensor_frame, 
double tf_tolerance);
 
   99   void bufferCloud(
const sensor_msgs::PointCloud2& cloud);
 
  149   boost::recursive_mutex 
lock_;  
 
  154 #endif  // COSTMAP_2D_OBSERVATION_BUFFER_H_ 
  
~ObservationBuffer()
Destructor... cleans up.
 
ObservationBuffer(std::string topic_name, double observation_keep_time, double expected_update_rate, double min_obstacle_height, double max_obstacle_height, double obstacle_range, double raytrace_range, tf2_ros::Buffer &tf2_buffer, std::string global_frame, std::string sensor_frame, double tf_tolerance)
Constructs an observation buffer.
 
bool isCurrent() const
Check if the observation buffer is being update at its expected rate.
 
tf2_ros::Buffer & tf2_buffer_
 
void purgeStaleObservations()
Removes any stale observations from the buffer list.
 
void resetLastUpdated()
Reset last updated timestamp.
 
std::string sensor_frame_
 
boost::recursive_mutex lock_
A lock for accessing data in callbacks safely.
 
bool setGlobalFrame(const std::string new_global_frame)
Sets the global frame of an observation buffer. This will transform all the currently cached observat...
 
void lock()
Lock the observation buffer.
 
const ros::Duration expected_update_rate_
 
std::list< Observation > observation_list_
 
void unlock()
Lock the observation buffer.
 
double min_obstacle_height_
 
void bufferCloud(const sensor_msgs::PointCloud2 &cloud)
Transforms a PointCloud to the global frame and buffers it Note: The burden is on the user to make su...
 
void getObservations(std::vector< Observation > &observations)
Pushes copies of all current observations onto the end of the vector passed in.
 
std::string global_frame_
 
double max_obstacle_height_
 
const ros::Duration observation_keep_time_
 
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17