Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_layer.cpp
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 
39 #include <nav2_costmap_2d/costmap_layer.hpp>
40 #include <stdexcept>
41 #include <algorithm>
42 
43 namespace nav2_costmap_2d
44 {
45 
47  double x, double y, double * min_x, double * min_y, double * max_x,
48  double * max_y)
49 {
50  *min_x = std::min(x, *min_x);
51  *min_y = std::min(y, *min_y);
52  *max_x = std::max(x, *max_x);
53  *max_y = std::max(y, *max_y);
54 }
55 
57 {
58  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
59  Costmap2D * master = layered_costmap_->getCostmap();
60  resizeMap(
61  master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
62  master->getOriginX(), master->getOriginY());
63 }
64 
65 void CostmapLayer::clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
66 {
67  current_ = false;
68  unsigned char * grid = getCharMap();
69 
70  int size_x = getSizeInCellsX();
71  int size_y = getSizeInCellsY();
72 
73  start_x = std::clamp(start_x, 0, size_x);
74  start_y = std::clamp(start_y, 0, size_y);
75  end_x = std::clamp(end_x, 0, size_x);
76  end_y = std::clamp(end_y, 0, size_y);
77 
78  for (int x = 0; x < size_x; x++) {
79  bool xrange = x > start_x && x < end_x;
80 
81  for (int y = 0; y < size_y; y++) {
82  if ((xrange && y > start_y && y < end_y) == invert) {
83  continue;
84  }
85  int index = getIndex(x, y);
86  if (grid[index] != NO_INFORMATION) {
87  grid[index] = NO_INFORMATION;
88  }
89  }
90  }
91 }
92 
93 void CostmapLayer::addExtraBounds(double mx0, double my0, double mx1, double my1)
94 {
95  extra_min_x_ = std::min(mx0, extra_min_x_);
96  extra_max_x_ = std::max(mx1, extra_max_x_);
97  extra_min_y_ = std::min(my0, extra_min_y_);
98  extra_max_y_ = std::max(my1, extra_max_y_);
99  has_extra_bounds_ = true;
100 }
101 
102 void CostmapLayer::useExtraBounds(double * min_x, double * min_y, double * max_x, double * max_y)
103 {
104  if (!has_extra_bounds_) {
105  return;
106  }
107 
108  *min_x = std::min(extra_min_x_, *min_x);
109  *min_y = std::min(extra_min_y_, *min_y);
110  *max_x = std::max(extra_max_x_, *max_x);
111  *max_y = std::max(extra_max_y_, *max_y);
112  extra_min_x_ = 1e6;
113  extra_min_y_ = 1e6;
114  extra_max_x_ = -1e6;
115  extra_max_y_ = -1e6;
116  has_extra_bounds_ = false;
117 }
118 
119 void CostmapLayer::updateWithMax(
120  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j,
121  int max_i,
122  int max_j)
123 {
124  if (!enabled_) {
125  return;
126  }
127 
128  unsigned char * master_array = master_grid.getCharMap();
129  unsigned int span = master_grid.getSizeInCellsX();
130 
131  for (int j = min_j; j < max_j; j++) {
132  unsigned int it = j * span + min_i;
133  for (int i = min_i; i < max_i; i++) {
134  if (costmap_[it] == NO_INFORMATION) {
135  it++;
136  continue;
137  }
138 
139  unsigned char old_cost = master_array[it];
140  if (old_cost == NO_INFORMATION || old_cost < costmap_[it]) {
141  master_array[it] = costmap_[it];
142  }
143  it++;
144  }
145  }
146 }
147 
148 void CostmapLayer::updateWithMaxWithoutUnknownOverwrite(
149  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j,
150  int max_i,
151  int max_j)
152 {
153  if (!enabled_) {
154  return;
155  }
156 
157  unsigned char * master_array = master_grid.getCharMap();
158  unsigned int span = master_grid.getSizeInCellsX();
159 
160  for (int j = min_j; j < max_j; j++) {
161  unsigned int it = j * span + min_i;
162  for (int i = min_i; i < max_i; i++) {
163  if (costmap_[it] == NO_INFORMATION) {
164  it++;
165  continue;
166  }
167 
168  unsigned char old_cost = master_array[it];
169  if (old_cost != NO_INFORMATION && old_cost < costmap_[it]) {
170  master_array[it] = costmap_[it];
171  }
172  it++;
173  }
174  }
175 }
176 
177 void CostmapLayer::updateWithTrueOverwrite(
178  nav2_costmap_2d::Costmap2D & master_grid, int min_i,
179  int min_j,
180  int max_i,
181  int max_j)
182 {
183  if (!enabled_) {
184  return;
185  }
186 
187  if (costmap_ == nullptr) {
188  throw std::runtime_error("Can't update costmap layer: It has't been initialized yet!");
189  }
190 
191  unsigned char * master = master_grid.getCharMap();
192  unsigned int span = master_grid.getSizeInCellsX();
193 
194  for (int j = min_j; j < max_j; j++) {
195  unsigned int it = span * j + min_i;
196  for (int i = min_i; i < max_i; i++) {
197  master[it] = costmap_[it];
198  it++;
199  }
200  }
201 }
202 
203 void CostmapLayer::updateWithOverwrite(
204  nav2_costmap_2d::Costmap2D & master_grid,
205  int min_i, int min_j, int max_i, int max_j)
206 {
207  if (!enabled_) {
208  return;
209  }
210  unsigned char * master = master_grid.getCharMap();
211  unsigned int span = master_grid.getSizeInCellsX();
212 
213  for (int j = min_j; j < max_j; j++) {
214  unsigned int it = span * j + min_i;
215  for (int i = min_i; i < max_i; i++) {
216  if (costmap_[it] != NO_INFORMATION) {
217  master[it] = costmap_[it];
218  }
219  it++;
220  }
221  }
222 }
223 
224 void CostmapLayer::updateWithAddition(
225  nav2_costmap_2d::Costmap2D & master_grid,
226  int min_i, int min_j, int max_i, int max_j)
227 {
228  if (!enabled_) {
229  return;
230  }
231  unsigned char * master_array = master_grid.getCharMap();
232  unsigned int span = master_grid.getSizeInCellsX();
233 
234  for (int j = min_j; j < max_j; j++) {
235  unsigned int it = j * span + min_i;
236  for (int i = min_i; i < max_i; i++) {
237  if (costmap_[it] == NO_INFORMATION) {
238  it++;
239  continue;
240  }
241 
242  unsigned char old_cost = master_array[it];
243  if (old_cost == NO_INFORMATION) {
244  master_array[it] = costmap_[it];
245  } else {
246  int sum = old_cost + costmap_[it];
247  if (sum >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
248  master_array[it] = nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1;
249  } else {
250  master_array[it] = sum;
251  }
252  }
253  it++;
254  }
255  }
256 }
257 
259 {
260  switch (value) {
261  case 0:
263  case 1:
264  return CombinationMethod::Max;
265  case 2:
267  default:
268  RCLCPP_WARN(
269  logger_,
270  "Param combination_method: %i. Possible values are 0 (Overwrite) or 1 (Maximum) or "
271  "2 (Maximum without overwriting the master's NO_INFORMATION values)."
272  "The default value 1 will be used", value);
273  return CombinationMethod::Max;
274  }
275 }
276 } // namespace nav2_costmap_2d
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:231
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
Definition: costmap_2d.cpp:110
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:571
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:566
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.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.