Skip to content

Commit 70af5ea

Browse files
Merge pull request #1 from moveit/jazzy
PSM: finish thread on rclcpp::shutdown (moveit#3484) (moveit#3486)
2 parents feef390 + 5450b9a commit 70af5ea

File tree

1 file changed

+3
-0
lines changed

1 file changed

+3
-0
lines changed

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
@@ -546,6 +546,9 @@ void PlanningSceneMonitor::scenePublishingThread()
546546
planning_scene_publisher_->publish(msg);
547547
if (is_full)
548548
RCLCPP_DEBUG(logger_, "Published full planning scene: '%s'", msg.name.c_str());
549+
// finish thread on rclcpp shutdown (otherwise rate.sleep() will crash)
550+
if (!rclcpp::ok())
551+
break;
549552
rate.sleep();
550553
}
551554
} while (publish_planning_scene_);

0 commit comments

Comments
 (0)