Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
costmap_layer.hpp
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  * David V. Lu!!
37  *********************************************************************/
38 #ifndef NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_
40 
41 #include <rclcpp/rclcpp.hpp>
42 #include <nav2_costmap_2d/layer.hpp>
43 #include <nav2_costmap_2d/layered_costmap.hpp>
44 
45 namespace nav2_costmap_2d
46 {
47 
54 class CostmapLayer : public Layer, public Costmap2D
55 {
56 public:
61  : has_extra_bounds_(false),
62  extra_min_x_(1e6), extra_max_x_(-1e6),
63  extra_min_y_(1e6), extra_max_y_(-1e6) {}
64 
69  {
70  return true;
71  }
72 
76  virtual void matchSize();
77 
82  virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert);
83 
93  void addExtraBounds(double mx0, double my0, double mx1, double my1);
94 
95 protected:
96  /*
97  * Updates the master_grid within the specified
98  * bounding box using this layer's values.
99  *
100  * TrueOverwrite means every value from this layer
101  * is written into the master grid.
102  */
103  void updateWithTrueOverwrite(
104  nav2_costmap_2d::Costmap2D & master_grid,
105  int min_i, int min_j, int max_i, int max_j);
106 
107  /*
108  * Updates the master_grid within the specified
109  * bounding box using this layer's values.
110  *
111  * Overwrite means every valid value from this layer
112  * is written into the master grid (does not copy NO_INFORMATION)
113  */
114  void updateWithOverwrite(
115  nav2_costmap_2d::Costmap2D & master_grid,
116  int min_i, int min_j, int max_i, int max_j);
117 
118  /*
119  * Updates the master_grid within the specified
120  * bounding box using this layer's values.
121  *
122  * Sets the new value to the maximum of the master_grid's value
123  * and this layer's value. If the master value is NO_INFORMATION,
124  * it is overwritten. If the layer's value is NO_INFORMATION,
125  * the master value does not change.
126  */
127  void updateWithMax(
128  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j, int max_i,
129  int max_j);
130 
131  /*
132  * Updates the master_grid within the specified
133  * bounding box using this layer's values.
134  *
135  * Sets the new value to the maximum of the master_grid's value
136  * and this layer's value. If the master value is NO_INFORMATION,
137  * it is NOT overwritten. If the layer's value is NO_INFORMATION,
138  * the master value does not change.
139  */
140  void updateWithMaxWithoutUnknownOverwrite(
141  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j, int max_i,
142  int max_j);
143 
144  /*
145  * Updates the master_grid within the specified
146  * bounding box using this layer's values.
147  *
148  * Sets the new value to the sum of the master grid's value
149  * and this layer's value. If the master value is NO_INFORMATION,
150  * it is overwritten with the layer's value. If the layer's value
151  * is NO_INFORMATION, then the master value does not change.
152  *
153  * If the sum value is larger than INSCRIBED_INFLATED_OBSTACLE,
154  * the master value is set to (INSCRIBED_INFLATED_OBSTACLE - 1).
155  */
156  void updateWithAddition(
157  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j, int max_i,
158  int max_j);
159 
171  void touch(double x, double y, double * min_x, double * min_y, double * max_x, double * max_y);
172 
173  /*
174  * Updates the bounding box specified in the parameters
175  * to include the bounding box from the addExtraBounds
176  * call. If addExtraBounds was not called, the method will do nothing.
177  *
178  * Should be called at the beginning of the updateBounds method
179  *
180  * @param min_x bounding box (input and output)
181  * @param min_y bounding box (input and output)
182  * @param max_x bounding box (input and output)
183  * @param max_y bounding box (input and output)
184  */
185  void useExtraBounds(double * min_x, double * min_y, double * max_x, double * max_y);
186  bool has_extra_bounds_;
187 
194 
195 private:
196  double extra_min_x_, extra_max_x_, extra_min_y_, extra_max_y_;
197 };
198 
199 } // namespace nav2_costmap_2d
200 #endif // NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
CostmapLayer()
CostmapLayer constructor.
bool isDiscretized()
If layer is discrete.
void addExtraBounds(double mx0, double my0, double mx1, double my1)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
Clear an are in the costmap with the given dimension if invert, then clear everything except these di...
virtual void matchSize()
Match the size of the master costmap.
CombinationMethod combination_method_from_int(const int value)
Converts an integer to a CombinationMethod enum and logs on failure.
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59