Skip to content

Commit d6f8c81

Browse files
temporary fix bug null pointer (#5749)
* temporary fix bug null pointer Signed-off-by: suifengersan123 <yangabc810@gmail.com> * add return Signed-off-by: suifengersan123 <yangabc810@gmail.com> * remove return Signed-off-by: suifengersan123 <yangabc810@gmail.com> --------- Signed-off-by: suifengersan123 <yangabc810@gmail.com>
1 parent 5068602 commit d6f8c81

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
@@ -57,6 +57,12 @@ void CostmapLayer::matchSize()
5757
{
5858
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
5959
Costmap2D * master = layered_costmap_->getCostmap();
60+
if (!master) {
61+
RCLCPP_WARN(
62+
rclcpp::get_logger("nav2_costmap_2d"),
63+
"Cannot match size for layer, master costmap is not initialized yet.");
64+
return;
65+
}
6066
resizeMap(
6167
master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
6268
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
@@ -117,7 +117,9 @@ void LayeredCostmap::resizeMap(
117117
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin();
118118
plugin != plugins_.end(); ++plugin)
119119
{
120-
(*plugin)->matchSize();
120+
if (*plugin) {
121+
(*plugin)->matchSize();
122+
}
121123
}
122124
for (vector<std::shared_ptr<Layer>>::iterator filter = filters_.begin();
123125
filter != filters_.end(); ++filter)

0 commit comments

Comments
 (0)