measurement_buffer.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2018, Simbe Robotics, 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 Simbe Robotics, 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: Steve Macenski (steven.macenski@simberobotics.com)
36  * Purpose: buffer incoming measurements for grid
37  *********************************************************************/
38 
39 #ifndef MEASUREMENT_BUFFER_H_
40 #define MEASUREMENT_BUFFER_H_
41 
42 // measurement structs
44 // PCL
45 #include <pcl_ros/transforms.h>
46 #include <pcl/filters/approximate_voxel_grid.h>
47 // STL
48 #include <vector>
49 #include <list>
50 #include <string>
51 // ROS
52 #include <ros/ros.h>
53 #include <ros/time.h>
54 // TF
55 #include <tf/transform_listener.h>
56 #include <tf/transform_datatypes.h>
57 // msgs
58 #include <sensor_msgs/PointCloud2.h>
59 #include <geometry_msgs/Quaternion.h>
60 // Mutex
61 #include <boost/thread.hpp>
62 
63 namespace buffer
64 {
65 
66 // conveniences for line lengths
67 typedef std::list<observation::MeasurementReading>::iterator readings_iter;
68 typedef pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_ptr;
69 
70 // Measurement buffer
72 {
73 public:
74  MeasurementBuffer(const std::string& topic_name, \
75  const double& observation_keep_time, \
76  const double& expected_update_rate, \
77  const double& min_obstacle_height, \
78  const double& max_obstacle_height, \
79  const double& obstacle_range, \
81  const std::string& global_frame, \
82  const std::string& sensor_frame, \
83  const double& tf_tolerance, \
84  const double& min_d, \
85  const double& max_d, \
86  const double& vFOV, \
87  const double& vFOVPadding, \
88  const double& hFOV, \
89  const double& decay_acceleration, \
90  const bool& marking, \
91  const bool& clearing, \
92  const double& voxel_size, \
93  const bool& voxel_filter, \
94  const bool& enabled, \
95  const bool& clear_buffer_after_reading, \
96  const ModelType& model_type);
97 
98  ~MeasurementBuffer(void);
99 
100  // Buffers for different types of pointclouds
101  void BufferROSCloud(const sensor_msgs::PointCloud2& cloud);
102  void BufferPCLCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud);
103 
104  // Get measurements from the buffer
105  void GetReadings(std::vector<observation::MeasurementReading>& observations);
106 
107  // enabler setter getter
108  bool IsEnabled(void) const;
109  void SetEnabled(const bool& enabled);
110 
111  // State knoweldge if sensors are operating as expected
112  bool UpdatedAtExpectedRate(void) const;
113  void ResetLastUpdatedTime(void);
114  void ResetAllMeasurements(void);
115  bool ClearAfterReading(void);
116 
117  // Public mutex locks
118  void Lock(void);
119  void Unlock(void);
120 
121 private:
122  // Removing old observations from buffer
123  void RemoveStaleObservations(void);
124 
127  boost::recursive_mutex _lock;
130  std::list<observation::MeasurementReading> _observation_list;
136 };
137 
138 } // namespace buffer
139 
140 #endif // MEASUREMENT_BUFFER_H_
void GetReadings(std::vector< observation::MeasurementReading > &observations)
void BufferPCLCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud)
pcl::PointCloud< pcl::PointXYZ >::Ptr point_cloud_ptr
bool UpdatedAtExpectedRate(void) const
void SetEnabled(const bool &enabled)
const ros::Duration _observation_keep_time
std::list< observation::MeasurementReading > _observation_list
boost::recursive_mutex _lock
tf::TransformListener & _tf
const ros::Duration _expected_update_rate
void BufferROSCloud(const sensor_msgs::PointCloud2 &cloud)
MeasurementBuffer(const std::string &topic_name, const double &observation_keep_time, const double &expected_update_rate, const double &min_obstacle_height, const double &max_obstacle_height, const double &obstacle_range, tf::TransformListener &tf, const std::string &global_frame, const std::string &sensor_frame, const double &tf_tolerance, const double &min_d, const double &max_d, const double &vFOV, const double &vFOVPadding, const double &hFOV, const double &decay_acceleration, const bool &marking, const bool &clearing, const double &voxel_size, const bool &voxel_filter, const bool &enabled, const bool &clear_buffer_after_reading, const ModelType &model_type)
std::list< observation::MeasurementReading >::iterator readings_iter


spatio_temporal_voxel_layer
Author(s):
autogenerated on Sat Dec 21 2019 04:06:19