Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed the problem of static layer not restoring old map values for footprint #4824

Merged
merged 21 commits into from
Feb 4, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
64efd40
Fix
CihatAltiparmak Dec 27, 2024
fbb3ff1
Fixed some bugs and removed the unnecessary variables from class
CihatAltiparmak Jan 4, 2025
bf3c0e1
Keep the branch updated with main
CihatAltiparmak Jan 10, 2025
9896607
Called off API changes in costmap, added "restore_outdated_footprint"
CihatAltiparmak Jan 10, 2025
d1554a5
Merge branch 'ros-navigation:main' into fix/static_map
CihatAltiparmak Jan 10, 2025
39f1f62
Added the documentation for the new methods in static layer
CihatAltiparmak Jan 10, 2025
d7bc96c
Make CI happy
CihatAltiparmak Jan 10, 2025
7b4cee3
Apply suggestions and minimize diffs
CihatAltiparmak Jan 16, 2025
0e9dbeb
Fix ament_cpp_lint
CihatAltiparmak Jan 16, 2025
2da4d29
Revert changes in the method updateFootprint
CihatAltiparmak Jan 27, 2025
d78274b
Used cached data to restore map and broken up setConvexPolygonCost in…
CihatAltiparmak Jan 29, 2025
a0657d2
Rename newly added methods
CihatAltiparmak Feb 1, 2025
1fa6a53
Merge branch 'ros-navigation:main' into fix/static_map
CihatAltiparmak Feb 1, 2025
833b983
Added restore_outdated_map parameter
CihatAltiparmak Feb 1, 2025
2322d98
Make CI happy
CihatAltiparmak Feb 1, 2025
fe4aec0
Changed the name of the newly added parameter
CihatAltiparmak Feb 3, 2025
04d3c38
Remove unnecessary log
CihatAltiparmak Feb 4, 2025
981cdd3
Add new member to MapLocation
CihatAltiparmak Feb 4, 2025
49916be
Remove unnecessary header
CihatAltiparmak Feb 4, 2025
1afd7b4
Set the parameters footprint_clearing_enabled and restore_cleared_foo…
CihatAltiparmak Feb 4, 2025
a3fd80b
Merge branch 'ros-navigation:main' into fix/static_map
CihatAltiparmak Feb 4, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 28 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ struct MapLocation
{
unsigned int x;
unsigned int y;
unsigned char cost;
};

/**
Expand Down Expand Up @@ -311,6 +312,32 @@ class Costmap2D
const std::vector<geometry_msgs::msg::Point> & polygon,
unsigned char cost_value);

/**
* @brief Gets the map region occupied by polygon
* @param polygon The polygon to perform the operation on
* @param polygon_map_region The map region occupied by the polygon
* @return True if the polygon_map_region was filled... false if it could not be filled
*/
bool getMapRegionOccupiedByPolygon(
const std::vector<geometry_msgs::msg::Point> & polygon,
std::vector<MapLocation> & polygon_map_region);

/**
* @brief Sets the given map region to desired value
* @param polygon_map_region The map region to perform the operation on
* @param new_cost_value The value to set costs to
*/
void setMapRegionOccupiedByPolygon(
const std::vector<MapLocation> & polygon_map_region,
unsigned char new_cost_value);

/**
* @brief Restores the corresponding map region using given map region
* @param polygon_map_region The map region to perform the operation on
*/
void restoreMapRegionOccupiedByPolygon(
const std::vector<MapLocation> & polygon_map_region);

/**
* @brief Get the map cells that make up the outline of a polygon
* @param polygon The polygon in map coordinates to rasterize
Expand Down Expand Up @@ -568,6 +595,7 @@ class Costmap2D
{
MapLocation loc;
costmap_.indexToCells(offset, loc.x, loc.y);
loc.cost = costmap_.getCost(loc.x, loc.y);
cells_.push_back(loc);
}

Expand Down
1 change: 1 addition & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,6 +163,7 @@ class StaticLayer : public CostmapLayer

std::vector<geometry_msgs::msg::Point> transformed_footprint_;
bool footprint_clearing_enabled_;
bool restore_cleared_footprint_;
/**
* @brief Clear costmap layer info below the robot's footprint
*/
Expand Down
19 changes: 18 additions & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
declareParameter("map_topic", rclcpp::ParameterValue("map"));
declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));
declareParameter("restore_cleared_footprint", rclcpp::ParameterValue(true));

auto node = node_.lock();
if (!node) {
Expand All @@ -147,6 +148,7 @@
node->get_parameter(name_ + "." + "enabled", enabled_);
node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_);
node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
node->get_parameter(name_ + "." + "restore_cleared_footprint", restore_cleared_footprint_);
node->get_parameter(name_ + "." + "map_topic", map_topic_);
map_topic_ = joinWithParentNamespace(map_topic_);
node->get_parameter(
Expand Down Expand Up @@ -411,8 +413,11 @@
return;
}

std::vector<MapLocation> map_region_to_restore;
if (footprint_clearing_enabled_) {
setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
map_region_to_restore.reserve(100);
getMapRegionOccupiedByPolygon(transformed_footprint_, map_region_to_restore);
setMapRegionOccupiedByPolygon(map_region_to_restore, nav2_costmap_2d::FREE_SPACE);
}

if (!layered_costmap_->isRolling()) {
Expand Down Expand Up @@ -458,6 +463,11 @@
}
}
}

CihatAltiparmak marked this conversation as resolved.
Show resolved Hide resolved
if (footprint_clearing_enabled_ && restore_cleared_footprint_) {
// restore the map region occupied by the polygon using cached data
restoreMapRegionOccupiedByPolygon(map_region_to_restore);
}
current_ = true;
}

Expand Down Expand Up @@ -498,6 +508,13 @@
current_ = false;
} else if (param_name == name_ + "." + "footprint_clearing_enabled") {
footprint_clearing_enabled_ = parameter.as_bool();
} else if (param_name == name_ + "." + "restore_cleared_footprint") {
if (footprint_clearing_enabled_) {
restore_cleared_footprint_ = parameter.as_bool();

Check warning on line 513 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L512-L513

Added lines #L512 - L513 were not covered by tests
} else {
RCLCPP_WARN(logger_, "restore_cleared_footprint cannot be used "

Check warning on line 515 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L515

Added line #L515 was not covered by tests
"when footprint_clearing_enabled is False. Rejecting parameter update.");
}
}
}
}
Expand Down
46 changes: 36 additions & 10 deletions nav2_costmap_2d/src/costmap_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -399,29 +399,54 @@ void Costmap2D::updateOrigin(double new_origin_x, double new_origin_y)
bool Costmap2D::setConvexPolygonCost(
const std::vector<geometry_msgs::msg::Point> & polygon,
unsigned char cost_value)
{
std::vector<MapLocation> polygon_map_region;
polygon_map_region.reserve(100);
if (!getMapRegionOccupiedByPolygon(polygon, polygon_map_region)) {
return false;
}

// set the cost of those cells
setMapRegionOccupiedByPolygon(polygon_map_region, cost_value);
return true;
}

void Costmap2D::setMapRegionOccupiedByPolygon(
const std::vector<MapLocation> & polygon_map_region,
unsigned char new_cost_value)
{
for (const auto & cell : polygon_map_region) {
setCost(cell.x, cell.y, new_cost_value);
}
}

void Costmap2D::restoreMapRegionOccupiedByPolygon(
const std::vector<MapLocation> & polygon_map_region)
{
for (const auto & cell : polygon_map_region) {
setCost(cell.x, cell.y, cell.cost);
}
}

bool Costmap2D::getMapRegionOccupiedByPolygon(
const std::vector<geometry_msgs::msg::Point> & polygon,
std::vector<MapLocation> & polygon_map_region)
{
// we assume the polygon is given in the global_frame...
// we need to transform it to map coordinates
std::vector<MapLocation> map_polygon;
for (unsigned int i = 0; i < polygon.size(); ++i) {
for (const auto & cell : polygon) {
MapLocation loc;
if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)) {
if (!worldToMap(cell.x, cell.y, loc.x, loc.y)) {
// ("Polygon lies outside map bounds, so we can't fill it");
return false;
}
map_polygon.push_back(loc);
}

std::vector<MapLocation> polygon_cells;

// get the cells that fill the polygon
convexFillCells(map_polygon, polygon_cells);
convexFillCells(map_polygon, polygon_map_region);

// set the cost of those cells
for (unsigned int i = 0; i < polygon_cells.size(); ++i) {
unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y);
costmap_[index] = cost_value;
}
return true;
}

Expand Down Expand Up @@ -506,6 +531,7 @@ void Costmap2D::convexFillCells(
for (unsigned int y = min_pt.y; y <= max_pt.y; ++y) {
pt.x = x;
pt.y = y;
pt.cost = getCost(x, y);
polygon_cells.push_back(pt);
}
}
Expand Down
2 changes: 2 additions & 0 deletions nav2_system_tests/src/system/nav2_system_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,8 @@ global_costmap:
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
footprint_clearing_enabled: True
restore_cleared_footprint: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
Expand Down
Loading