Skip to content

Commit 9896607

Browse files
Called off API changes in costmap, added "restore_outdated_footprint"
Signed-off-by: CihatAltiparmak <[email protected]>
1 parent bf3c0e1 commit 9896607

File tree

4 files changed

+78
-50
lines changed

4 files changed

+78
-50
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp

-32
Original file line numberDiff line numberDiff line change
@@ -163,8 +163,6 @@ class Costmap2D
163163
*/
164164
void setCost(unsigned int mx, unsigned int my, unsigned char cost);
165165

166-
void setCost(unsigned int index, unsigned char cost);
167-
168166
/**
169167
* @brief Convert from map coordinates to world coordinates
170168
* @param mx The x map coordinate
@@ -313,36 +311,6 @@ class Costmap2D
313311
const std::vector<geometry_msgs::msg::Point> & polygon,
314312
unsigned char cost_value);
315313

316-
template<typename CostSetter>
317-
bool setConvexPolygonCost(
318-
const std::vector<geometry_msgs::msg::Point> & polygon,
319-
CostSetter cost_setter)
320-
{
321-
// we assume the polygon is given in the global_frame...
322-
// we need to transform it to map coordinates
323-
std::vector<MapLocation> map_polygon;
324-
for (unsigned int i = 0; i < polygon.size(); ++i) {
325-
MapLocation loc;
326-
if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)) {
327-
// ("Polygon lies outside map bounds, so we can't fill it");
328-
return false;
329-
}
330-
map_polygon.push_back(loc);
331-
}
332-
333-
std::vector<MapLocation> polygon_cells;
334-
335-
// get the cells that fill the polygon
336-
convexFillCells(map_polygon, polygon_cells);
337-
338-
// set the cost of those cells
339-
for (unsigned int i = 0; i < polygon_cells.size(); ++i) {
340-
unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y);
341-
costmap_[index] = cost_setter(index);
342-
}
343-
return true;
344-
}
345-
346314
/**
347315
* @brief Get the map cells that make up the outline of a polygon
348316
* @param polygon The polygon in map coordinates to rasterize

nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp

+14-1
Original file line numberDiff line numberDiff line change
@@ -154,6 +154,17 @@ class StaticLayer : public CostmapLayer
154154
*/
155155
unsigned char interpretValue(unsigned char value);
156156

157+
void getCellsOccupiedByFootprint(
158+
std::vector<MapLocation> & cells_occupied_by_footprint,
159+
const std::vector<geometry_msgs::msg::Point> & footprint);
160+
161+
void resetCells(
162+
const std::vector<MapLocation> & resetting_cells, unsigned char cost);
163+
164+
void restoreCellsFromMap(
165+
const std::vector<MapLocation> & restoring_cells,
166+
const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer);
167+
157168
/**
158169
* @brief Callback executed when a parameter change is detected
159170
* @param event ParameterEvent message
@@ -162,8 +173,10 @@ class StaticLayer : public CostmapLayer
162173
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
163174

164175
std::vector<geometry_msgs::msg::Point> transformed_footprint_;
165-
std::vector<unsigned int> cleared_indexes_in_map_;
176+
std::vector<MapLocation> cells_cleared_by_footprint_;
166177
bool footprint_clearing_enabled_;
178+
bool restore_outdated_footprint_;
179+
167180
/**
168181
* @brief Clear costmap layer info below the robot's footprint
169182
*/

nav2_costmap_2d/plugins/static_layer.cpp

+64-12
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,7 @@ StaticLayer::getParameters()
138138
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
139139
declareParameter("map_topic", rclcpp::ParameterValue("map"));
140140
declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));
141+
declareParameter("restore_outdated_footprint", rclcpp::ParameterValue(false));
141142

142143
auto node = node_.lock();
143144
if (!node) {
@@ -147,6 +148,7 @@ StaticLayer::getParameters()
147148
node->get_parameter(name_ + "." + "enabled", enabled_);
148149
node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_);
149150
node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
151+
node->get_parameter(name_ + "." + "restore_outdated_footprint", restore_outdated_footprint_);
150152
node->get_parameter(name_ + "." + "map_topic", map_topic_);
151153
map_topic_ = joinWithParentNamespace(map_topic_);
152154
node->get_parameter(
@@ -322,6 +324,46 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u
322324
has_updated_data_ = true;
323325
}
324326

327+
void
328+
StaticLayer::getCellsOccupiedByFootprint(
329+
std::vector<MapLocation> & cells_occupied_by_footprint,
330+
const std::vector<geometry_msgs::msg::Point> & footprint)
331+
{
332+
// we assume the polygon is given in the global_frame...
333+
// we need to transform it to map coordinates
334+
std::vector<MapLocation> map_polygon;
335+
for (const auto & point : footprint) {
336+
MapLocation loc;
337+
if (!this->worldToMap(point.x, point.y, loc.x, loc.y)) {
338+
// ("Polygon lies outside map bounds, so we can't fill it");
339+
return;
340+
}
341+
map_polygon.push_back(loc);
342+
}
343+
344+
// get the cells that fill the polygon
345+
this->convexFillCells(map_polygon, cells_occupied_by_footprint);
346+
}
347+
348+
void StaticLayer::resetCells(
349+
const std::vector<MapLocation> & resetting_cells, unsigned char cost)
350+
{
351+
352+
for (const auto & cell : resetting_cells) {
353+
setCost(cell.x, cell.y, cost);
354+
}
355+
}
356+
357+
void StaticLayer::restoreCellsFromMap(
358+
const std::vector<MapLocation> & restoring_cells,
359+
const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer)
360+
{
361+
362+
for (const auto & cell : restoring_cells) {
363+
unsigned int index = getIndex(cell.x, cell.y);
364+
costmap_[index] = interpretValue(map_buffer->data[index]);
365+
}
366+
}
325367

326368
void
327369
StaticLayer::updateBounds(
@@ -374,10 +416,17 @@ StaticLayer::updateFootprint(
374416
{
375417
if (!footprint_clearing_enabled_) {return;}
376418

419+
if (restore_outdated_footprint_) {
420+
// Increase the bounds to make the outdated footprint restored by layered costmap
421+
for (const auto & point : transformed_footprint_) {
422+
touch(point.x, point.y, min_x, min_y, max_x, max_y);
423+
}
424+
}
425+
377426
transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
378427

379-
for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
380-
touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
428+
for (const auto & point : transformed_footprint_) {
429+
touch(point.x, point.y, min_x, min_y, max_x, max_y);
381430
}
382431
}
383432

@@ -400,6 +449,17 @@ StaticLayer::updateCosts(
400449
return;
401450
}
402451

452+
if (footprint_clearing_enabled_) {
453+
if (restore_outdated_footprint_) {
454+
restoreCellsFromMap(cells_cleared_by_footprint_, map_buffer_);
455+
}
456+
457+
cells_cleared_by_footprint_.clear();
458+
getCellsOccupiedByFootprint(cells_cleared_by_footprint_, transformed_footprint_);
459+
460+
resetCells(cells_cleared_by_footprint_, nav2_costmap_2d::FREE_SPACE);
461+
}
462+
403463
if (!layered_costmap_->isRolling()) {
404464
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
405465
if (!use_maximum_) {
@@ -444,16 +504,6 @@ StaticLayer::updateCosts(
444504
}
445505
}
446506

447-
if (footprint_clearing_enabled_) {
448-
for (const auto index : cleared_indexes_in_map_) {
449-
master_grid.setCost(index, interpretValue(map_buffer_->data[index]));
450-
}
451-
cleared_indexes_in_map_.clear();
452-
master_grid.setConvexPolygonCost(transformed_footprint_, [this](unsigned int index) {
453-
cleared_indexes_in_map_.push_back(index);
454-
return nav2_costmap_2d::FREE_SPACE;
455-
});
456-
}
457507
current_ = true;
458508
}
459509

@@ -496,6 +546,8 @@ StaticLayer::dynamicParametersCallback(
496546
} else if (param_type == ParameterType::PARAMETER_BOOL) {
497547
if (param_name == name_ + "." + "footprint_clearing_enabled") {
498548
footprint_clearing_enabled_ = parameter.as_bool();
549+
} else if (param_name == name_ + "." + "restore_outdated_footprint") {
550+
restore_outdated_footprint_ = parameter.as_bool();
499551
}
500552
}
501553
}

nav2_costmap_2d/src/costmap_2d.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -276,11 +276,6 @@ void Costmap2D::setCost(unsigned int mx, unsigned int my, unsigned char cost)
276276
costmap_[getIndex(mx, my)] = cost;
277277
}
278278

279-
void Costmap2D::setCost(unsigned int index, unsigned char cost)
280-
{
281-
costmap_[index] = cost;
282-
}
283-
284279
void Costmap2D::mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const
285280
{
286281
wx = origin_x_ + (mx + 0.5) * resolution_;

0 commit comments

Comments
 (0)