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> 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);
154 #endif // COSTMAP_2D_OBSERVATION_BUFFER_H_ boost::recursive_mutex lock_
A lock for accessing data in callbacks safely.
void getObservations(std::vector< Observation > &observations)
Pushes copies of all current observations onto the end of the vector passed in.
double max_obstacle_height_
void unlock()
Lock the observation buffer.
std::string global_frame_
std::string sensor_frame_
bool isCurrent() const
Check if the observation buffer is being update at its expected rate.
void lock()
Lock the observation buffer.
bool setGlobalFrame(const std::string new_global_frame)
Sets the global frame of an observation buffer. This will transform all the currently cached observat...
Takes in point clouds from sensors, transforms them to the desired frame, and stores them...
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...
~ObservationBuffer()
Destructor... cleans up.
void resetLastUpdated()
Reset last updated timestamp.
void purgeStaleObservations()
Removes any stale observations from the buffer list.
const ros::Duration expected_update_rate_
std::list< Observation > observation_list_
const ros::Duration observation_keep_time_
double min_obstacle_height_
tf2_ros::Buffer & tf2_buffer_
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.