From 9b277126026a2eaad97a7c78b385a31e8d2d40b4 Mon Sep 17 00:00:00 2001 From: Joey Yang Date: Thu, 4 Jul 2024 11:42:29 -0400 Subject: [PATCH] Return out of map update if frames mismatch. Signed-off-by Joey Yang (#4517) Signed-off-by: Joey Yang --- nav2_costmap_2d/plugins/static_layer.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 729530d82b..25a10e3bd8 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -318,6 +318,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u "StaticLayer: Map update ignored. Current map is in frame %s " "but update was in frame %s", map_frame_.c_str(), update->header.frame_id.c_str()); + return; } unsigned int di = 0;