Nav2 Navigation Stack - humble  humble
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  Costmap2D * master = layered_costmap_->getCostmap();
59  resizeMap(
60  master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
61  master->getOriginX(), master->getOriginY());
62 }
63 
64 void CostmapLayer::clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
65 {
66  current_ = false;
67  unsigned char * grid = getCharMap();
68  for (int x = 0; x < static_cast<int>(getSizeInCellsX()); x++) {
69  bool xrange = x > start_x && x < end_x;
70 
71  for (int y = 0; y < static_cast<int>(getSizeInCellsY()); y++) {
72  if ((xrange && y > start_y && y < end_y) == invert) {
73  continue;
74  }
75  int index = getIndex(x, y);
76  if (grid[index] != NO_INFORMATION) {
77  grid[index] = NO_INFORMATION;
78  }
79  }
80  }
81 }
82 
83 void CostmapLayer::addExtraBounds(double mx0, double my0, double mx1, double my1)
84 {
85  extra_min_x_ = std::min(mx0, extra_min_x_);
86  extra_max_x_ = std::max(mx1, extra_max_x_);
87  extra_min_y_ = std::min(my0, extra_min_y_);
88  extra_max_y_ = std::max(my1, extra_max_y_);
89  has_extra_bounds_ = true;
90 }
91 
92 void CostmapLayer::useExtraBounds(double * min_x, double * min_y, double * max_x, double * max_y)
93 {
94  if (!has_extra_bounds_) {
95  return;
96  }
97 
98  *min_x = std::min(extra_min_x_, *min_x);
99  *min_y = std::min(extra_min_y_, *min_y);
100  *max_x = std::max(extra_max_x_, *max_x);
101  *max_y = std::max(extra_max_y_, *max_y);
102  extra_min_x_ = 1e6;
103  extra_min_y_ = 1e6;
104  extra_max_x_ = -1e6;
105  extra_max_y_ = -1e6;
106  has_extra_bounds_ = false;
107 }
108 
109 void CostmapLayer::updateWithMax(
110  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j,
111  int max_i,
112  int max_j)
113 {
114  if (!enabled_) {
115  return;
116  }
117 
118  unsigned char * master_array = master_grid.getCharMap();
119  unsigned int span = master_grid.getSizeInCellsX();
120 
121  for (int j = min_j; j < max_j; j++) {
122  unsigned int it = j * span + min_i;
123  for (int i = min_i; i < max_i; i++) {
124  if (costmap_[it] == NO_INFORMATION) {
125  it++;
126  continue;
127  }
128 
129  unsigned char old_cost = master_array[it];
130  if (old_cost == NO_INFORMATION || old_cost < costmap_[it]) {
131  master_array[it] = costmap_[it];
132  }
133  it++;
134  }
135  }
136 }
137 
138 void CostmapLayer::updateWithTrueOverwrite(
139  nav2_costmap_2d::Costmap2D & master_grid, int min_i,
140  int min_j,
141  int max_i,
142  int max_j)
143 {
144  if (!enabled_) {
145  return;
146  }
147 
148  if (costmap_ == nullptr) {
149  throw std::runtime_error("Can't update costmap layer: It has't been initialized yet!");
150  }
151 
152  unsigned char * master = master_grid.getCharMap();
153  unsigned int span = master_grid.getSizeInCellsX();
154 
155  for (int j = min_j; j < max_j; j++) {
156  unsigned int it = span * j + min_i;
157  for (int i = min_i; i < max_i; i++) {
158  master[it] = costmap_[it];
159  it++;
160  }
161  }
162 }
163 
164 void CostmapLayer::updateWithOverwrite(
165  nav2_costmap_2d::Costmap2D & master_grid,
166  int min_i, int min_j, int max_i, int max_j)
167 {
168  if (!enabled_) {
169  return;
170  }
171  unsigned char * master = master_grid.getCharMap();
172  unsigned int span = master_grid.getSizeInCellsX();
173 
174  for (int j = min_j; j < max_j; j++) {
175  unsigned int it = span * j + min_i;
176  for (int i = min_i; i < max_i; i++) {
177  if (costmap_[it] != NO_INFORMATION) {
178  master[it] = costmap_[it];
179  }
180  it++;
181  }
182  }
183 }
184 
185 void CostmapLayer::updateWithAddition(
186  nav2_costmap_2d::Costmap2D & master_grid,
187  int min_i, int min_j, int max_i, int max_j)
188 {
189  if (!enabled_) {
190  return;
191  }
192  unsigned char * master_array = master_grid.getCharMap();
193  unsigned int span = master_grid.getSizeInCellsX();
194 
195  for (int j = min_j; j < max_j; j++) {
196  unsigned int it = j * span + min_i;
197  for (int i = min_i; i < max_i; i++) {
198  if (costmap_[it] == NO_INFORMATION) {
199  it++;
200  continue;
201  }
202 
203  unsigned char old_cost = master_array[it];
204  if (old_cost == NO_INFORMATION) {
205  master_array[it] = costmap_[it];
206  } else {
207  int sum = old_cost + costmap_[it];
208  if (sum >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
209  master_array[it] = nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1;
210  } else {
211  master_array[it] = sum;
212  }
213  }
214  it++;
215  }
216  }
217 }
218 } // 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:211
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:108
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:261
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:531
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:526
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:521
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.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.