diff --git a/nav2_costmap_2d/src/footprint_subscriber.cpp b/nav2_costmap_2d/src/footprint_subscriber.cpp index 29a275d0348..f87d7d7f1b1 100644 --- a/nav2_costmap_2d/src/footprint_subscriber.cpp +++ b/nav2_costmap_2d/src/footprint_subscriber.cpp @@ -59,9 +59,10 @@ FootprintSubscriber::getFootprint( return false; } + auto current_footprint = std::atomic_load(&footprint_); footprint = toPointVector( - std::make_shared(footprint_->polygon)); - auto & footprint_stamp = footprint_->header.stamp; + std::make_shared(current_footprint->polygon)); + auto & footprint_stamp = current_footprint->header.stamp; if (stamp - footprint_stamp > valid_footprint_timeout) { return false; @@ -89,7 +90,7 @@ FootprintSubscriber::getFootprint( void FootprintSubscriber::footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg) { - footprint_ = msg; + std::atomic_store(&footprint_, msg); if (!footprint_received_) { footprint_received_ = true; }