38 #ifndef COSTMAP_PROHIBITION_LAYER_H_ 39 #define COSTMAP_PROHIBITION_LAYER_H_ 45 #include <geometry_msgs/PoseArray.h> 50 #include <costmap_prohibition_layer/CostmapProhibitionLayerConfig.h> 51 #include <dynamic_reconfigure/server.h> 53 #include <unordered_map> 83 virtual void onInitialize();
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);
99 int max_i,
int max_j);
106 void reconfigureCB(CostmapProhibitionLayerConfig& config, uint32_t level);
112 void computeMapBounds();
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);
139 void rasterizePolygon(
const std::vector<PointInt>& polygon, std::vector<PointInt>& polygon_cells,
bool fill);
150 void polygonOutlineCells(
const std::vector<PointInt>& polygon, std::vector<PointInt>& polygon_cells);
166 void raytrace(
int x0,
int y0,
int x1,
int y1, std::vector<PointInt>& cells);
196 dynamic_reconfigure::Server<CostmapProhibitionLayerConfig>*
_dsrv;
bool param(const std::string ¶m_name, T ¶m_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