Nav2 Navigation Stack - kilted  kilted
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  footprint_(std::make_shared<std::vector<geometry_msgs::msg::Point>>())
73 {
74  if (track_unknown) {
75  primary_costmap_.setDefaultValue(NO_INFORMATION);
76  combined_costmap_.setDefaultValue(NO_INFORMATION);
77  } else {
78  primary_costmap_.setDefaultValue(FREE_SPACE);
79  combined_costmap_.setDefaultValue(FREE_SPACE);
80  }
81 }
82 
84 {
85  while (plugins_.size() > 0) {
86  plugins_.pop_back();
87  }
88  while (filters_.size() > 0) {
89  filters_.pop_back();
90  }
91 }
92 
93 void LayeredCostmap::addPlugin(std::shared_ptr<Layer> plugin)
94 {
95  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
96  plugins_.push_back(plugin);
97 }
98 
99 void LayeredCostmap::addFilter(std::shared_ptr<Layer> filter)
100 {
101  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
102  filters_.push_back(filter);
103 }
104 
106  unsigned int size_x, unsigned int size_y, double resolution,
107  double origin_x,
108  double origin_y,
109  bool size_locked)
110 {
111  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
112  size_locked_ = size_locked;
113  primary_costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
114  combined_costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
115  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
116  plugin != plugins_.end(); ++plugin)
117  {
118  (*plugin)->matchSize();
119  }
120  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
121  filter != filters_.end(); ++filter)
122  {
123  (*filter)->matchSize();
124  }
125 }
126 
127 bool LayeredCostmap::isOutofBounds(double robot_x, double robot_y)
128 {
129  unsigned int mx, my;
130  return !combined_costmap_.worldToMap(robot_x, robot_y, mx, my);
131 }
132 
133 void LayeredCostmap::updateMap(double robot_x, double robot_y, double robot_yaw)
134 {
135  // Lock for the remainder of this function, some plugins (e.g. VoxelLayer)
136  // implement thread unsafe updateBounds() functions.
137  std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
138 
139  // if we're using a rolling buffer costmap...
140  // we need to update the origin using the robot's position
141  if (rolling_window_) {
142  double new_origin_x = robot_x - combined_costmap_.getSizeInMetersX() / 2;
143  double new_origin_y = robot_y - combined_costmap_.getSizeInMetersY() / 2;
144  primary_costmap_.updateOrigin(new_origin_x, new_origin_y);
145  combined_costmap_.updateOrigin(new_origin_x, new_origin_y);
146  }
147 
148  if (isOutofBounds(robot_x, robot_y)) {
149  RCLCPP_WARN(
150  rclcpp::get_logger("nav2_costmap_2d"),
151  "Robot is out of bounds of the costmap!");
152  }
153 
154  if (plugins_.size() == 0 && filters_.size() == 0) {
155  return;
156  }
157 
158  minx_ = miny_ = std::numeric_limits<double>::max();
159  maxx_ = maxy_ = std::numeric_limits<double>::lowest();
160 
161  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
162  plugin != plugins_.end(); ++plugin)
163  {
164  double prev_minx = minx_;
165  double prev_miny = miny_;
166  double prev_maxx = maxx_;
167  double prev_maxy = maxy_;
168  (*plugin)->updateBounds(robot_x, robot_y, robot_yaw, &minx_, &miny_, &maxx_, &maxy_);
169  if (minx_ > prev_minx || miny_ > prev_miny || maxx_ < prev_maxx || maxy_ < prev_maxy) {
170  RCLCPP_WARN(
171  rclcpp::get_logger(
172  "nav2_costmap_2d"), "Illegal bounds change, was [tl: (%f, %f), br: (%f, %f)], but "
173  "is now [tl: (%f, %f), br: (%f, %f)]. The offending layer is %s",
174  prev_minx, prev_miny, prev_maxx, prev_maxy,
175  minx_, miny_, maxx_, maxy_,
176  (*plugin)->getName().c_str());
177  }
178  }
179  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
180  filter != filters_.end(); ++filter)
181  {
182  double prev_minx = minx_;
183  double prev_miny = miny_;
184  double prev_maxx = maxx_;
185  double prev_maxy = maxy_;
186  (*filter)->updateBounds(robot_x, robot_y, robot_yaw, &minx_, &miny_, &maxx_, &maxy_);
187  if (minx_ > prev_minx || miny_ > prev_miny || maxx_ < prev_maxx || maxy_ < prev_maxy) {
188  RCLCPP_WARN(
189  rclcpp::get_logger(
190  "nav2_costmap_2d"), "Illegal bounds change, was [tl: (%f, %f), br: (%f, %f)], but "
191  "is now [tl: (%f, %f), br: (%f, %f)]. The offending filter is %s",
192  prev_minx, prev_miny, prev_maxx, prev_maxy,
193  minx_, miny_, maxx_, maxy_,
194  (*filter)->getName().c_str());
195  }
196  }
197 
198  int x0, xn, y0, yn;
199  combined_costmap_.worldToMapEnforceBounds(minx_, miny_, x0, y0);
200  combined_costmap_.worldToMapEnforceBounds(maxx_, maxy_, xn, yn);
201 
202  x0 = std::max(0, x0);
203  xn = std::min(static_cast<int>(combined_costmap_.getSizeInCellsX()), xn + 1);
204  y0 = std::max(0, y0);
205  yn = std::min(static_cast<int>(combined_costmap_.getSizeInCellsY()), yn + 1);
206 
207  RCLCPP_DEBUG(
208  rclcpp::get_logger(
209  "nav2_costmap_2d"), "Updating area x: [%d, %d] y: [%d, %d]", x0, xn, y0, yn);
210 
211  if (xn < x0 || yn < y0) {
212  return;
213  }
214 
215  if (filters_.size() == 0) {
216  // If there are no filters enabled just update costmap sequentially by each plugin
217  combined_costmap_.resetMap(x0, y0, xn, yn);
218  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
219  plugin != plugins_.end(); ++plugin)
220  {
221  (*plugin)->updateCosts(combined_costmap_, x0, y0, xn, yn);
222  }
223  } else {
224  // Costmap Filters enabled
225  // 1. Update costmap by plugins
226  primary_costmap_.resetMap(x0, y0, xn, yn);
227  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
228  plugin != plugins_.end(); ++plugin)
229  {
230  (*plugin)->updateCosts(primary_costmap_, x0, y0, xn, yn);
231  }
232 
233  // 2. Copy processed costmap window to a final costmap.
234  // primary_costmap_ remain to be untouched for further usage by plugins.
235  if (!combined_costmap_.copyWindow(primary_costmap_, x0, y0, xn, yn, x0, y0)) {
236  RCLCPP_ERROR(
237  rclcpp::get_logger("nav2_costmap_2d"),
238  "Can not copy costmap (%i,%i)..(%i,%i) window",
239  x0, y0, xn, yn);
240  throw std::runtime_error{"Can not copy costmap"};
241  }
242 
243  // 3. Apply filters over the plugins in order to make filters' work
244  // not being considered by plugins on next updateMap() calls
245  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
246  filter != filters_.end(); ++filter)
247  {
248  (*filter)->updateCosts(combined_costmap_, x0, y0, xn, yn);
249  }
250  }
251 
252  bx0_ = x0;
253  bxn_ = xn;
254  by0_ = y0;
255  byn_ = yn;
256 
257  initialized_ = true;
258 }
259 
261 {
262  current_ = true;
263  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
264  plugin != plugins_.end(); ++plugin)
265  {
266  current_ = current_ && ((*plugin)->isCurrent() || !(*plugin)->isEnabled());
267  }
268  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
269  filter != filters_.end(); ++filter)
270  {
271  current_ = current_ && ((*filter)->isCurrent() || !(*filter)->isEnabled());
272  }
273  return current_;
274 }
275 
276 void LayeredCostmap::setFootprint(const std::vector<geometry_msgs::msg::Point> & footprint_spec)
277 {
278  std::pair<double, double> inside_outside = nav2_costmap_2d::calculateMinAndMaxDistances(
279  footprint_spec);
280  // use atomic store here since footprint is used by various planners/controllers
281  // and not otherwise locked
282  std::atomic_store(
283  &footprint_,
284  std::make_shared<std::vector<geometry_msgs::msg::Point>>(footprint_spec));
285  inscribed_radius_.store(std::get<0>(inside_outside));
286  circumscribed_radius_.store(std::get<1>(inside_outside));
287 
288  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
289  plugin != plugins_.end();
290  ++plugin)
291  {
292  (*plugin)->onFootprintChanged();
293  }
294  for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
295  filter != filters_.end();
296  ++filter)
297  {
298  (*filter)->onFootprintChanged();
299  }
300 }
301 
302 } // 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:110
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:184
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:327
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:291
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
Definition: costmap_2d.hpp:300
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:349
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:561
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:556
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
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...
std::pair< double, double > calculateMinAndMaxDistances(const std::vector< geometry_msgs::msg::Point > &footprint)
Calculate the extreme distances for the footprint.
Definition: footprint.cpp:43