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