Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
layered_costmap.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 #include "nav2_costmap_2d/layered_costmap.hpp"
39 
40 #include <algorithm>
41 #include <cstdio>
42 #include <memory>
43 #include <string>
44 #include <vector>
45 #include <limits>
46 
47 #include "nav2_costmap_2d/footprint.hpp"
48 
49 
50 using std::vector;
51 
52 namespace nav2_costmap_2d
53 {
54 
55 LayeredCostmap::LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown)
56 : primary_costmap_(), combined_costmap_(),
57  global_frame_(global_frame),
58  rolling_window_(rolling_window),
59  current_(false),
60  minx_(0.0),
61  miny_(0.0),
62  maxx_(0.0),
63  maxy_(0.0),
64  bx0_(0),
65  bxn_(0),
66  by0_(0),
67  byn_(0),
68  initialized_(false),
69  size_locked_(false),
70  circumscribed_radius_(1.0),
71  inscribed_radius_(0.1)
72 {
73  if (track_unknown) {
74  primary_costmap_.setDefaultValue(255);
75  combined_costmap_.setDefaultValue(255);
76  } else {
77  primary_costmap_.setDefaultValue(0);
78  combined_costmap_.setDefaultValue(0);
79  }
80 }
81 
83 {
84  while (plugins_.size() > 0) {
85  plugins_.pop_back();
86  }
87  while (filters_.size() > 0) {
88  filters_.pop_back();
89  }
90 }
91 
92 void LayeredCostmap::addPlugin(std::shared_ptr<Layer> plugin)
93 {
94  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
95  plugins_.push_back(plugin);
96 }
97 
98 void LayeredCostmap::addFilter(std::shared_ptr<Layer> filter)
99 {
100  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
101  filters_.push_back(filter);
102 }
103 
105  unsigned int size_x, unsigned int size_y, double resolution,
106  double origin_x,
107  double origin_y,
108  bool size_locked)
109 {
110  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
111  size_locked_ = size_locked;
112  primary_costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
113  combined_costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
114  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
115  plugin != plugins_.end(); ++plugin)
116  {
117  (*plugin)->matchSize();
118  }
119  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
120  filter != filters_.end(); ++filter)
121  {
122  (*filter)->matchSize();
123  }
124 }
125 
126 bool LayeredCostmap::isOutofBounds(double robot_x, double robot_y)
127 {
128  unsigned int mx, my;
129  return !combined_costmap_.worldToMap(robot_x, robot_y, mx, my);
130 }
131 
132 void LayeredCostmap::updateMap(double robot_x, double robot_y, double robot_yaw)
133 {
134  // Lock for the remainder of this function, some plugins (e.g. VoxelLayer)
135  // implement thread unsafe updateBounds() functions.
136  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
137 
138  // if we're using a rolling buffer costmap...
139  // we need to update the origin using the robot's position
140  if (rolling_window_) {
141  double new_origin_x = robot_x - combined_costmap_.getSizeInMetersX() / 2;
142  double new_origin_y = robot_y - combined_costmap_.getSizeInMetersY() / 2;
143  primary_costmap_.updateOrigin(new_origin_x, new_origin_y);
144  combined_costmap_.updateOrigin(new_origin_x, new_origin_y);
145  }
146 
147  if (isOutofBounds(robot_x, robot_y)) {
148  RCLCPP_WARN(
149  rclcpp::get_logger("nav2_costmap_2d"),
150  "Robot is out of bounds of the costmap!");
151  }
152 
153  if (plugins_.size() == 0 && filters_.size() == 0) {
154  return;
155  }
156 
157  minx_ = miny_ = std::numeric_limits<double>::max();
158  maxx_ = maxy_ = std::numeric_limits<double>::lowest();
159 
160  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
161  plugin != plugins_.end(); ++plugin)
162  {
163  double prev_minx = minx_;
164  double prev_miny = miny_;
165  double prev_maxx = maxx_;
166  double prev_maxy = maxy_;
167  (*plugin)->updateBounds(robot_x, robot_y, robot_yaw, &minx_, &miny_, &maxx_, &maxy_);
168  if (minx_ > prev_minx || miny_ > prev_miny || maxx_ < prev_maxx || maxy_ < prev_maxy) {
169  RCLCPP_WARN(
170  rclcpp::get_logger(
171  "nav2_costmap_2d"), "Illegal bounds change, was [tl: (%f, %f), br: (%f, %f)], but "
172  "is now [tl: (%f, %f), br: (%f, %f)]. The offending layer is %s",
173  prev_minx, prev_miny, prev_maxx, prev_maxy,
174  minx_, miny_, maxx_, maxy_,
175  (*plugin)->getName().c_str());
176  }
177  }
178  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
179  filter != filters_.end(); ++filter)
180  {
181  double prev_minx = minx_;
182  double prev_miny = miny_;
183  double prev_maxx = maxx_;
184  double prev_maxy = maxy_;
185  (*filter)->updateBounds(robot_x, robot_y, robot_yaw, &minx_, &miny_, &maxx_, &maxy_);
186  if (minx_ > prev_minx || miny_ > prev_miny || maxx_ < prev_maxx || maxy_ < prev_maxy) {
187  RCLCPP_WARN(
188  rclcpp::get_logger(
189  "nav2_costmap_2d"), "Illegal bounds change, was [tl: (%f, %f), br: (%f, %f)], but "
190  "is now [tl: (%f, %f), br: (%f, %f)]. The offending filter is %s",
191  prev_minx, prev_miny, prev_maxx, prev_maxy,
192  minx_, miny_, maxx_, maxy_,
193  (*filter)->getName().c_str());
194  }
195  }
196 
197  int x0, xn, y0, yn;
198  combined_costmap_.worldToMapEnforceBounds(minx_, miny_, x0, y0);
199  combined_costmap_.worldToMapEnforceBounds(maxx_, maxy_, xn, yn);
200 
201  x0 = std::max(0, x0);
202  xn = std::min(static_cast<int>(combined_costmap_.getSizeInCellsX()), xn + 1);
203  y0 = std::max(0, y0);
204  yn = std::min(static_cast<int>(combined_costmap_.getSizeInCellsY()), yn + 1);
205 
206  RCLCPP_DEBUG(
207  rclcpp::get_logger(
208  "nav2_costmap_2d"), "Updating area x: [%d, %d] y: [%d, %d]", x0, xn, y0, yn);
209 
210  if (xn < x0 || yn < y0) {
211  return;
212  }
213 
214  if (filters_.size() == 0) {
215  // If there are no filters enabled just update costmap sequentially by each plugin
216  combined_costmap_.resetMap(x0, y0, xn, yn);
217  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
218  plugin != plugins_.end(); ++plugin)
219  {
220  (*plugin)->updateCosts(combined_costmap_, x0, y0, xn, yn);
221  }
222  } else {
223  // Costmap Filters enabled
224  // 1. Update costmap by plugins
225  primary_costmap_.resetMap(x0, y0, xn, yn);
226  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
227  plugin != plugins_.end(); ++plugin)
228  {
229  (*plugin)->updateCosts(primary_costmap_, x0, y0, xn, yn);
230  }
231 
232  // 2. Copy processed costmap window to a final costmap.
233  // primary_costmap_ remain to be untouched for further usage by plugins.
234  if (!combined_costmap_.copyWindow(primary_costmap_, x0, y0, xn, yn, x0, y0)) {
235  RCLCPP_ERROR(
236  rclcpp::get_logger("nav2_costmap_2d"),
237  "Can not copy costmap (%i,%i)..(%i,%i) window",
238  x0, y0, xn, yn);
239  throw std::runtime_error{"Can not copy costmap"};
240  }
241 
242  // 3. Apply filters over the plugins in order to make filters' work
243  // not being considered by plugins on next updateMap() calls
244  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
245  filter != filters_.end(); ++filter)
246  {
247  (*filter)->updateCosts(combined_costmap_, x0, y0, xn, yn);
248  }
249  }
250 
251  bx0_ = x0;
252  bxn_ = xn;
253  by0_ = y0;
254  byn_ = yn;
255 
256  initialized_ = true;
257 }
258 
260 {
261  current_ = true;
262  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
263  plugin != plugins_.end(); ++plugin)
264  {
265  current_ = current_ && ((*plugin)->isCurrent() || !(*plugin)->isEnabled());
266  }
267  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
268  filter != filters_.end(); ++filter)
269  {
270  current_ = current_ && ((*filter)->isCurrent() || !(*filter)->isEnabled());
271  }
272  return current_;
273 }
274 
275 void LayeredCostmap::setFootprint(const std::vector<geometry_msgs::msg::Point> & footprint_spec)
276 {
277  footprint_ = footprint_spec;
279  footprint_spec,
280  inscribed_radius_, circumscribed_radius_);
281 
282  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
283  plugin != plugins_.end();
284  ++plugin)
285  {
286  (*plugin)->onFootprintChanged();
287  }
288  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
289  filter != filters_.end();
290  ++filter)
291  {
292  (*filter)->onFootprintChanged();
293  }
294 }
295 
296 } // namespace nav2_costmap_2d
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
Definition: costmap_2d.cpp:130
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
bool copyWindow(const Costmap2D &source, unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn, unsigned int dx0, unsigned int dy0)
Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap.
Definition: costmap_2d.cpp:187
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
Definition: costmap_2d.cpp:308
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:287
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
Definition: costmap_2d.hpp:280
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
Definition: costmap_2d.cpp:330
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:516
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:511
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
void addPlugin(std::shared_ptr< Layer > plugin)
Add a new plugin to the plugins vector to process.
void addFilter(std::shared_ptr< Layer > filter)
Add a new costmap filter plugin to the filters vector to process.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Resize the map to a new size, resolution, or origin.
bool isOutofBounds(double robot_x, double robot_y)
Checks if the robot is outside the bounds of its costmap in the case of poorly configured setups.
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown)
Constructor for a costmap.
void setFootprint(const std::vector< geometry_msgs::msg::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
bool isCurrent()
If the costmap is current, e.g. are all the layers processing recent data and not stale information f...
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::msg::Point > &footprint, double &min_dist, double &max_dist)
Calculate the extreme distances for the footprint.
Definition: footprint.cpp:43