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),
72 footprint_(std::make_shared<std::vector<geometry_msgs::msg::Point>>())
85 while (plugins_.size() > 0) {
88 while (filters_.size() > 0) {
95 std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
96 plugins_.push_back(plugin);
101 std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
102 filters_.push_back(filter);
106 unsigned int size_x,
unsigned int size_y,
double resolution,
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)
118 (*plugin)->matchSize();
120 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
121 filter != filters_.end(); ++filter)
123 (*filter)->matchSize();
130 return !combined_costmap_.
worldToMap(robot_x, robot_y, mx, my);
137 std::unique_lock<Costmap2D::mutex_t> lock(*(combined_costmap_.getMutex()));
141 if (rolling_window_) {
144 primary_costmap_.
updateOrigin(new_origin_x, new_origin_y);
145 combined_costmap_.
updateOrigin(new_origin_x, new_origin_y);
150 rclcpp::get_logger(
"nav2_costmap_2d"),
151 "Robot is out of bounds of the costmap!");
154 if (plugins_.size() == 0 && filters_.size() == 0) {
158 minx_ = miny_ = std::numeric_limits<double>::max();
159 maxx_ = maxy_ = std::numeric_limits<double>::lowest();
161 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
162 plugin != plugins_.end(); ++plugin)
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) {
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());
179 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
180 filter != filters_.end(); ++filter)
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) {
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());
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);
209 "nav2_costmap_2d"),
"Updating area x: [%d, %d] y: [%d, %d]", x0, xn, y0, yn);
211 if (xn < x0 || yn < y0) {
215 if (filters_.size() == 0) {
217 combined_costmap_.
resetMap(x0, y0, xn, yn);
218 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
219 plugin != plugins_.end(); ++plugin)
221 (*plugin)->updateCosts(combined_costmap_, x0, y0, xn, yn);
226 primary_costmap_.
resetMap(x0, y0, xn, yn);
227 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
228 plugin != plugins_.end(); ++plugin)
230 (*plugin)->updateCosts(primary_costmap_, x0, y0, xn, yn);
235 if (!combined_costmap_.
copyWindow(primary_costmap_, x0, y0, xn, yn, x0, y0)) {
237 rclcpp::get_logger(
"nav2_costmap_2d"),
238 "Can not copy costmap (%i,%i)..(%i,%i) window",
240 throw std::runtime_error{
"Can not copy costmap"};
245 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
246 filter != filters_.end(); ++filter)
248 (*filter)->updateCosts(combined_costmap_, x0, y0, xn, yn);
263 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
264 plugin != plugins_.end(); ++plugin)
266 current_ = current_ && ((*plugin)->isCurrent() || !(*plugin)->isEnabled());
268 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
269 filter != filters_.end(); ++filter)
271 current_ = current_ && ((*filter)->isCurrent() || !(*filter)->isEnabled());
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));
288 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
289 plugin != plugins_.end();
292 (*plugin)->onFootprintChanged();
294 for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
295 filter != filters_.end();
298 (*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...
std::pair< double, double > calculateMinAndMaxDistances(const std::vector< geometry_msgs::msg::Point > &footprint)
Calculate the extreme distances for the footprint.