Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
12 changes: 12 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "rclcpp/rclcpp.hpp"
#include "nav2_costmap_2d/footprint.hpp"

namespace nav2_costmap_2d
{
Expand Down Expand Up @@ -160,6 +161,17 @@ class StaticLayer : public CostmapLayer
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);

std::vector<geometry_msgs::msg::Point> transformed_footprint_;
bool footprint_clearing_enabled_;
/**
* @brief Clear costmap layer info below the robot's footprint
*/
void updateFootprint(
double robot_x, double robot_y, double robot_yaw, double * min_x,
double * min_y,
double * max_x,
double * max_y);

std::string global_frame_; ///< @brief The global frame for the costmap
std::string map_frame_; /// @brief frame that map is located in

Expand Down
30 changes: 29 additions & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,7 @@ StaticLayer::getParameters()
declareParameter("map_subscribe_transient_local", rclcpp::ParameterValue(true));
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
declareParameter("map_topic", rclcpp::ParameterValue(""));
declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));

auto node = node_.lock();
if (!node) {
Expand All @@ -141,6 +142,7 @@ StaticLayer::getParameters()

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_);
std::string private_map_topic, global_map_topic;
node->get_parameter(name_ + "." + "map_topic", private_map_topic);
node->get_parameter("map_topic", global_map_topic);
Expand Down Expand Up @@ -333,7 +335,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u

void
StaticLayer::updateBounds(
double /*robot_x*/, double /*robot_y*/, double /*robot_yaw*/, double * min_x,
double robot_x, double robot_y, double robot_yaw, double * min_x,
double * min_y,
double * max_x,
double * max_y)
Expand Down Expand Up @@ -371,6 +373,24 @@ StaticLayer::updateBounds(
*max_y = std::max(wy, *max_y);

has_updated_data_ = false;

updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
}

void
StaticLayer::updateFootprint(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y,
double * max_x,
double * max_y)
{
if (!footprint_clearing_enabled_) {return;}

transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);

for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
}
}

void
Expand All @@ -392,6 +412,10 @@ StaticLayer::updateCosts(
return;
}

if (footprint_clearing_enabled_) {
setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
}

if (!layered_costmap_->isRolling()) {
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
if (!use_maximum_) {
Expand Down Expand Up @@ -474,6 +498,10 @@ StaticLayer::dynamicParametersCallback(
has_updated_data_ = true;
current_ = false;
}
} else if (param_type == ParameterType::PARAMETER_BOOL) {
if (param_name == name_ + "." + "footprint_clearing_enabled") {
footprint_clearing_enabled_ = parameter.as_bool();
}
}
}
result.successful = true;
Expand Down