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
6 changes: 6 additions & 0 deletions nav2_costmap_2d/src/costmap_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,12 @@ void CostmapLayer::matchSize()
{
std::lock_guard<Costmap2D::mutex_t> 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());
Expand Down
4 changes: 3 additions & 1 deletion nav2_costmap_2d/src/layered_costmap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,9 @@ void LayeredCostmap::resizeMap(
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
plugin != plugins_.end(); ++plugin)
{
(*plugin)->matchSize();
if (*plugin) {
(*plugin)->matchSize();
}
}
for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
filter != filters_.end(); ++filter)
Expand Down
Loading