38 #include "nav2_costmap_2d/layered_costmap.hpp"
47 #include "nav2_costmap_2d/footprint.hpp"
56 : primary_costmap_(), combined_costmap_(),
57 global_frame_(global_frame),
58 rolling_window_(rolling_window),
70 circumscribed_radius_(1.0),
71 inscribed_radius_(0.1)
84 while (plugins_.size() > 0) {
87 while (filters_.size() > 0) {
94 std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
95 plugins_.push_back(plugin);
100 std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
101 filters_.push_back(filter);
105 unsigned int size_x,
unsigned int size_y,
double resolution,
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)
117 (*plugin)->matchSize();
119 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
120 filter != filters_.end(); ++filter)
122 (*filter)->matchSize();
129 return !combined_costmap_.
worldToMap(robot_x, robot_y, mx, my);
136 std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
140 if (rolling_window_) {
143 primary_costmap_.
updateOrigin(new_origin_x, new_origin_y);
144 combined_costmap_.
updateOrigin(new_origin_x, new_origin_y);
149 rclcpp::get_logger(
"nav2_costmap_2d"),
150 "Robot is out of bounds of the costmap!");
153 if (plugins_.size() == 0 && filters_.size() == 0) {
157 minx_ = miny_ = std::numeric_limits<double>::max();
158 maxx_ = maxy_ = std::numeric_limits<double>::lowest();
160 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
161 plugin != plugins_.end(); ++plugin)
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) {
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());
178 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
179 filter != filters_.end(); ++filter)
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) {
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());
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);
208 "nav2_costmap_2d"),
"Updating area x: [%d, %d] y: [%d, %d]", x0, xn, y0, yn);
210 if (xn < x0 || yn < y0) {
214 if (filters_.size() == 0) {
216 combined_costmap_.
resetMap(x0, y0, xn, yn);
217 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
218 plugin != plugins_.end(); ++plugin)
220 (*plugin)->updateCosts(combined_costmap_, x0, y0, xn, yn);
225 primary_costmap_.
resetMap(x0, y0, xn, yn);
226 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
227 plugin != plugins_.end(); ++plugin)
229 (*plugin)->updateCosts(primary_costmap_, x0, y0, xn, yn);
234 if (!combined_costmap_.
copyWindow(primary_costmap_, x0, y0, xn, yn, x0, y0)) {
236 rclcpp::get_logger(
"nav2_costmap_2d"),
237 "Can not copy costmap (%i,%i)..(%i,%i) window",
239 throw std::runtime_error{
"Can not copy costmap"};
244 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
245 filter != filters_.end(); ++filter)
247 (*filter)->updateCosts(combined_costmap_, x0, y0, xn, yn);
262 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
263 plugin != plugins_.end(); ++plugin)
265 current_ = current_ && ((*plugin)->isCurrent() || !(*plugin)->isEnabled());
267 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
268 filter != filters_.end(); ++filter)
270 current_ = current_ && ((*filter)->isCurrent() || !(*filter)->isEnabled());
277 footprint_ = footprint_spec;
280 inscribed_radius_, circumscribed_radius_);
282 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
283 plugin != plugins_.end();
286 (*plugin)->onFootprintChanged();
288 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
289 filter != filters_.end();
292 (*filter)->onFootprintChanged();
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
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.
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
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.
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
void addPlugin(std::shared_ptr< Layer > plugin)
Add a new plugin to the plugins vector to process.
~LayeredCostmap()
Destructor.
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.