Skip to content

Commit 0211977

Browse files
author
随风而散
committed
temporary fix bug null pointer
1 parent 81969ef commit 0211977

File tree

2 files changed

+9
-1
lines changed

2 files changed

+9
-1
lines changed

nav2_costmap_2d/src/costmap_layer.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,12 @@ void CostmapLayer::touch(
5656
void CostmapLayer::matchSize()
5757
{
5858
Costmap2D * master = layered_costmap_->getCostmap();
59+
if (!master) {
60+
RCLCPP_WARN(
61+
rclcpp::get_logger("nav2_costmap_2d"),
62+
"Cannot match size for layer, master costmap is not initialized yet.");
63+
return;
64+
}
5965
resizeMap(
6066
master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
6167
master->getOriginX(), master->getOriginY());

nav2_costmap_2d/src/layered_costmap.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,9 @@ void LayeredCostmap::resizeMap(
9696
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
9797
plugin != plugins_.end(); ++plugin)
9898
{
99-
(*plugin)->matchSize();
99+
if (*plugin) {
100+
(*plugin)->matchSize();
101+
}
100102
}
101103
}
102104

0 commit comments

Comments
 (0)