costmap_prohibition_layer.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Stephan Kurzawe
37  *********************************************************************/
38 #ifndef COSTMAP_PROHIBITION_LAYER_H_
39 #define COSTMAP_PROHIBITION_LAYER_H_
40 
41 #include <XmlRpcValue.h>
42 #include <XmlRpcException.h>
43 #include <tf/transform_datatypes.h>
44 #include <mutex>
45 #include <geometry_msgs/PoseArray.h>
46 #include <stdlib.h>
47 #include <ros/ros.h>
48 #include <costmap_2d/layer.h>
50 #include <costmap_prohibition_layer/CostmapProhibitionLayerConfig.h>
51 #include <dynamic_reconfigure/server.h>
52 
53 #include <unordered_map>
54 
56 {
57 
58 // point with integer coordinates
59 struct PointInt
60 {
61  int x;
62  int y;
63 };
64 
66 {
67 public:
68 
73 
77  virtual ~CostmapProhibitionLayer();
83  virtual void onInitialize();
84 
90  virtual void updateBounds(double robot_x, double robot_y, double robot_yaw,
91  double *min_x, double *min_y, double *max_x, double *max_y);
92 
98  virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j,
99  int max_i, int max_j);
100 
101 private:
102 
106  void reconfigureCB(CostmapProhibitionLayerConfig& config, uint32_t level);
107 
112  void computeMapBounds();
113 
126  void setPolygonCost(costmap_2d::Costmap2D &master_grid, const std::vector<geometry_msgs::Point>& polygon,
127  unsigned char cost, int min_i, int min_j, int max_i, int max_j, bool fill_polygon);
128 
139  void rasterizePolygon(const std::vector<PointInt>& polygon, std::vector<PointInt>& polygon_cells, bool fill);
140 
150  void polygonOutlineCells(const std::vector<PointInt>& polygon, std::vector<PointInt>& polygon_cells);
151 
166  void raytrace(int x0, int y0, int x1, int y1, std::vector<PointInt>& cells);
167 
168 
182  bool parseProhibitionListFromYaml(ros::NodeHandle* nhandle, const std::string& param);
183 
194  bool getPoint(XmlRpc::XmlRpcValue& val, geometry_msgs::Point& point);
195 
196  dynamic_reconfigure::Server<CostmapProhibitionLayerConfig>* _dsrv;
197  std::mutex _data_mutex;
200  std::vector<geometry_msgs::Point> _prohibition_points;
201  std::vector<std::vector<geometry_msgs::Point>> _prohibition_polygons;
202  double _min_x, _min_y, _max_x, _max_y;
203 };
204 }
205 #endif
bool param(const std::string &param_name, T &param_val, const T &default_val)
std::vector< geometry_msgs::Point > _prohibition_points
vector to save the lonely points in source coordinates
bool _fill_polygons
if true, all cells that are located in the interior of polygons are marked as obstacle as well ...
std::mutex _data_mutex
mutex for the accessing _prohibition_points and _prohibition_polygons
dynamic_reconfigure::Server< CostmapProhibitionLayerConfig > * _dsrv
dynamic_reconfigure server for the costmap
double _costmap_resolution
resolution of the overlayed costmap to create the thinnest line out of two points ...
std::vector< std::vector< geometry_msgs::Point > > _prohibition_polygons
vector to save the polygons (including lines) in source coordinates


costmap_prohibition_layer
Author(s): Stephan Kurzawe
autogenerated on Mon Jun 10 2019 13:05:00