From 2edfb83152f71e771b683c6f834ed1c69b62fbe4 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Mon, 14 Oct 2019 20:14:04 -0700 Subject: [PATCH] Set map_received to true --- nav2_costmap_2d/plugins/static_layer.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 8d78f4a89ab..7a04b24739f 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -139,6 +139,7 @@ StaticLayer::getParameters() // Enforce bounds lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0); + map_received_ = false; } void @@ -241,6 +242,9 @@ StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map) { std::lock_guard guard(*getMutex()); processMap(*new_map); + if (!map_received_) { + map_received_ = true; + } } void