diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 799c5df0f2a..48699378b70 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -531,18 +531,25 @@ void PlanningSceneMonitor::newPlanningSceneCallback(const moveit_msgs::PlanningS void PlanningSceneMonitor::clearOctomap() { - if (scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS)) - triggerSceneUpdateEvent(UPDATE_SCENE); - if (octomap_monitor_) - { - octomap_monitor_->getOcTreePtr()->lockWrite(); - octomap_monitor_->getOcTreePtr()->clear(); - octomap_monitor_->getOcTreePtr()->unlockWrite(); - } - else + bool removed = false; { - ROS_WARN_NAMED(LOGNAME, "Unable to clear octomap since no octomap monitor has been initialized"); + boost::unique_lock ulock(scene_update_mutex_); + removed = scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS); + + if (octomap_monitor_) + { + octomap_monitor_->getOcTreePtr()->lockWrite(); + octomap_monitor_->getOcTreePtr()->clear(); + octomap_monitor_->getOcTreePtr()->unlockWrite(); + } + else + { + ROS_WARN_NAMED(LOGNAME, "Unable to clear octomap since no octomap monitor has been initialized"); + } // Lift the scoped lock before calling triggerSceneUpdateEvent to avoid deadlock } + + if (removed) + triggerSceneUpdateEvent(UPDATE_GEOMETRY); } bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningScene& scene)