spatio_temporal_voxel_layer.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: Replace the ROS voxel grid / obstacle layers using VoxelGrid
37  * with OpenVDB's more efficient and capacble voxel library with
38  * ray tracing and knn.
39  *********************************************************************/
40 
41 #ifndef VOLUME_GRID_LAYER_H_
42 #define VOLUME_GRID_LAYER_H_
43 
44 // voxel grid
46 #include <spatio_temporal_voxel_layer/SpatioTemporalVoxelLayerConfig.h>
47 // ROS
48 #include <ros/ros.h>
50 #include <dynamic_reconfigure/server.h>
51 // costmap
52 #include <costmap_2d/layer.h>
55 #include <costmap_2d/footprint.h>
56 // openVDB
57 #include <openvdb/openvdb.h>
58 // STL
59 #include <vector>
60 #include <string>
61 #include <iostream>
62 #include <time.h>
63 // msgs
64 #include <sensor_msgs/LaserScan.h>
65 #include <sensor_msgs/PointCloud2.h>
67 #include <geometry_msgs/Point.h>
68 #include <spatio_temporal_voxel_layer/SaveGrid.h>
69 #include <std_srvs/SetBool.h>
70 // projector
72 // tf
73 #include <tf/message_filter.h>
74 #include <tf/exceptions.h>
75 
77 {
78 
79 // conveniences for line lengths
80 typedef std::vector<boost::shared_ptr<message_filters::SubscriberBase> >::iterator observation_subscribers_iter;
81 typedef std::vector<boost::shared_ptr<buffer::MeasurementBuffer> >::iterator observation_buffers_iter;
82 typedef spatio_temporal_voxel_layer::SpatioTemporalVoxelLayerConfig dynamicReconfigureType;
83 typedef dynamic_reconfigure::Server<dynamicReconfigureType> dynamicReconfigureServerType;
84 
85 // Core ROS voxel layer class
87 {
88 public:
90  virtual ~SpatioTemporalVoxelLayer(void);
91 
92  // Core Functions
93  virtual void onInitialize(void);
94  virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, \
95  double* min_x, double* min_y, double* max_x, double* max_y);
96  virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, \
97  int max_i, int max_j);
98 
99  // Functions to interact with other layers
100  virtual void matchSize(void);
101 
102  // Functions for layer high level operations
103  virtual void reset(void);
104  virtual void activate(void);
105  virtual void deactivate(void);
106 
107 
108  // Functions for sensor feeds
109  bool GetMarkingObservations(std::vector<observation::MeasurementReading>& marking_observations) const;
110  bool GetClearingObservations(std::vector<observation::MeasurementReading>& marking_observations) const;
111  void ObservationsResetAfterReading() const;
112 
113  // Functions to interact with maps
114  void UpdateROSCostmap(double* min_x, double* min_y, double* max_x, double* max_y);
115  bool updateFootprint(double robot_x, double robot_y, double robot_yaw, \
116  double* min_x, double* min_y, double* max_x, double* max_y);
117  void ResetGrid(void);
118 
119  // Saving grids callback for openVDB
120  bool SaveGridCallback(spatio_temporal_voxel_layer::SaveGrid::Request& req, \
121  spatio_temporal_voxel_layer::SaveGrid::Response& resp);
122 
123 private:
124  // Sensor callbacks
125  void LaserScanCallback(const sensor_msgs::LaserScanConstPtr& message, \
127  void LaserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& raw_message, \
129  void PointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message, \
131 
132  // Functions for adding static obstacle zones
134  bool RemoveStaticObservations(void);
135 
136  // Dynamic reconfigure
137  void DynamicReconfigureCallback(dynamicReconfigureType &config, uint32_t level);
138 
139  // Enable/Disable callback
140  bool BufferEnablerCallback( std_srvs::SetBool::Request & request, \
141  std_srvs::SetBool::Response & response, \
144 
145 
147  std::vector<boost::shared_ptr<message_filters::SubscriberBase> > _observation_subscribers;
148  std::vector<boost::shared_ptr<tf::MessageFilterBase> > _observation_notifiers;
149  std::vector<boost::shared_ptr<buffer::MeasurementBuffer> > _observation_buffers;
150  std::vector<boost::shared_ptr<buffer::MeasurementBuffer> > _marking_buffers;
151  std::vector<boost::shared_ptr<buffer::MeasurementBuffer> > _clearing_buffers;
152  std::vector<ros::ServiceServer> _buffer_enabler_servers;
153  dynamicReconfigureServerType* _dynamic_reconfigure_server;
154 
160  std::string _global_frame;
165  std::vector<geometry_msgs::Point> _transformed_footprint;
166  std::vector<observation::MeasurementReading> _static_observations;
168  boost::recursive_mutex _voxel_grid_lock;
169 };
170 
171 }; // end namespace
172 #endif
void PointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< buffer::MeasurementBuffer > &buffer)
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > >::iterator observation_buffers_iter
void UpdateROSCostmap(double *min_x, double *min_y, double *max_x, double *max_y)
bool updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
dynamic_reconfigure::Server< dynamicReconfigureType > dynamicReconfigureServerType
void LaserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr &raw_message, const boost::shared_ptr< buffer::MeasurementBuffer > &buffer)
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > > _observation_buffers
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > > _marking_buffers
std::vector< boost::shared_ptr< tf::MessageFilterBase > > _observation_notifiers
bool GetClearingObservations(std::vector< observation::MeasurementReading > &marking_observations) const
std::vector< boost::shared_ptr< message_filters::SubscriberBase > >::iterator observation_subscribers_iter
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > _observation_subscribers
std::vector< boost::shared_ptr< buffer::MeasurementBuffer > > _clearing_buffers
spatio_temporal_voxel_layer::SpatioTemporalVoxelLayerConfig dynamicReconfigureType
bool GetMarkingObservations(std::vector< observation::MeasurementReading > &marking_observations) const
bool AddStaticObservations(const observation::MeasurementReading &obs)
bool SaveGridCallback(spatio_temporal_voxel_layer::SaveGrid::Request &req, spatio_temporal_voxel_layer::SaveGrid::Response &resp)
bool BufferEnablerCallback(std_srvs::SetBool::Request &request, std_srvs::SetBool::Response &response, boost::shared_ptr< buffer::MeasurementBuffer > &buffer, boost::shared_ptr< message_filters::SubscriberBase > &subcriber)
std::vector< observation::MeasurementReading > _static_observations
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
void DynamicReconfigureCallback(dynamicReconfigureType &config, uint32_t level)
void LaserScanCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< buffer::MeasurementBuffer > &buffer)


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