observation_buffer.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  *********************************************************************/
37 #ifndef COSTMAP_2D_OBSERVATION_BUFFER_H_
38 #define COSTMAP_2D_OBSERVATION_BUFFER_H_
39 
40 #include <vector>
41 #include <list>
42 #include <string>
43 #include <ros/time.h>
44 #include <costmap_2d/observation.h>
45 #include <tf/transform_listener.h>
46 #include <tf/transform_datatypes.h>
47 
48 // PCL Stuff
49 #include <pcl/point_cloud.h>
50 #include <sensor_msgs/PointCloud2.h>
51 
52 // Thread support
53 #include <boost/thread.hpp>
54 
55 namespace costmap_2d
56 {
62 {
63 public:
78  ObservationBuffer(std::string topic_name, double observation_keep_time, double expected_update_rate,
79  double min_obstacle_height, double max_obstacle_height, double obstacle_range,
80  double raytrace_range, tf::TransformListener& tf, std::string global_frame,
81  std::string sensor_frame, double tf_tolerance);
82 
87 
95  bool setGlobalFrame(const std::string new_global_frame);
96 
102  void bufferCloud(const sensor_msgs::PointCloud2& cloud);
103 
109  void bufferCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud);
110 
115  void getObservations(std::vector<Observation>& observations);
116 
121  bool isCurrent() const;
122 
126  inline void lock()
127  {
128  lock_.lock();
129  }
130 
134  inline void unlock()
135  {
136  lock_.unlock();
137  }
138 
142  void resetLastUpdated();
143 
144 private:
148  void purgeStaleObservations();
149 
154  std::string global_frame_;
155  std::string sensor_frame_;
156  std::list<Observation> observation_list_;
157  std::string topic_name_;
159  boost::recursive_mutex lock_;
162 };
163 } // namespace costmap_2d
164 #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.
tf::TransformListener & tf_
void unlock()
Lock the observation buffer.
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.
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, tf::TransformListener &tf, std::string global_frame, std::string sensor_frame, double tf_tolerance)
Constructs an observation buffer.
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_
bool isCurrent() const
Check if the observation buffer is being update at its expected rate.


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:42