Skip to content

Commit

Permalink
Only set if it is not nullptr
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Aug 6, 2024
1 parent e3b3dde commit 165a922
Showing 1 changed file with 10 additions and 3 deletions.
13 changes: 10 additions & 3 deletions moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,10 @@ PlanningScene::PlanningScene(const PlanningSceneConstPtr& parent) : parent_(pare

setStateFeasibilityPredicate(parent->getStateFeasibilityPredicate());
setMotionFeasibilityPredicate(parent->getMotionFeasibilityPredicate());
setCollisionObjectUpdateCallback(parent_->current_world_object_update_callback_);
if (parent_->current_world_object_update_callback_)
{
setCollisionObjectUpdateCallback(parent_->current_world_object_update_callback_);
}

// maintain a separate world. Copy on write ensures that most of the object
// info is shared until it is modified.
Expand Down Expand Up @@ -1214,8 +1217,12 @@ void PlanningScene::decoupleParent()
(object_types_.value())[it->first] = it->second;
}
}
current_world_object_update_callback_ = parent_->current_world_object_update_callback_;
setCollisionObjectUpdateCallback(current_world_object_update_callback_);

if (parent_->current_world_object_update_callback_)
{
current_world_object_update_callback_ = parent_->current_world_object_update_callback_;
setCollisionObjectUpdateCallback(current_world_object_update_callback_);
}

parent_.reset();
}
Expand Down

0 comments on commit 165a922

Please sign in to comment.