diff --git a/nav2_costmap_2d/src/costmap_layer.cpp b/nav2_costmap_2d/src/costmap_layer.cpp index 9b597962d10..a5323fc6c95 100644 --- a/nav2_costmap_2d/src/costmap_layer.cpp +++ b/nav2_costmap_2d/src/costmap_layer.cpp @@ -57,6 +57,12 @@ void CostmapLayer::matchSize() { std::lock_guard guard(*getMutex()); Costmap2D * master = layered_costmap_->getCostmap(); + if (!master) { + RCLCPP_WARN( + rclcpp::get_logger("nav2_costmap_2d"), + "Cannot match size for layer, master costmap is not initialized yet."); + return; + } resizeMap( master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(), master->getOriginX(), master->getOriginY()); diff --git a/nav2_costmap_2d/src/layered_costmap.cpp b/nav2_costmap_2d/src/layered_costmap.cpp index a551ec70e20..bef1cb97837 100644 --- a/nav2_costmap_2d/src/layered_costmap.cpp +++ b/nav2_costmap_2d/src/layered_costmap.cpp @@ -117,7 +117,9 @@ void LayeredCostmap::resizeMap( for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); ++plugin) { - (*plugin)->matchSize(); + if (*plugin) { + (*plugin)->matchSize(); + } } for (vector>::iterator filter = filters_.begin(); filter != filters_.end(); ++filter)