Skip to content

Commit 3f2d7f5

Browse files
authored
Check rclcpp::ok before sleeping for clean shutdown (backport moveit#3484) (moveit#3485)
1 parent a60ed9f commit 3f2d7f5

1 file changed

Lines changed: 3 additions & 0 deletions

File tree

moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -492,6 +492,9 @@ void PlanningSceneMonitor::scenePublishingThread()
492492
planning_scene_publisher_->publish(msg);
493493
if (is_full)
494494
RCLCPP_DEBUG(LOGGER, "Published full planning scene: '%s'", msg.name.c_str());
495+
// finish thread on rclcpp shutdown (otherwise rate.sleep() will crash)
496+
if (!rclcpp::ok())
497+
break;
495498
rate.sleep();
496499
}
497500
} while (publish_planning_scene_);

0 commit comments

Comments
 (0)