Skip to content

Commit f81636b

Browse files
MarqRazzmergify[bot]
authored andcommitted
PSM: finish thread on rclcpp::shutdown (#3484)
Calling rate.sleep() on shutdown will crash (cherry picked from commit f4cf780) # Conflicts: # moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp
1 parent a60ed9f commit f81636b

File tree

1 file changed

+7
-0
lines changed

1 file changed

+7
-0
lines changed

moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -491,7 +491,14 @@ void PlanningSceneMonitor::scenePublishingThread()
491491
{
492492
planning_scene_publisher_->publish(msg);
493493
if (is_full)
494+
<<<<<<< HEAD
494495
RCLCPP_DEBUG(LOGGER, "Published full planning scene: '%s'", msg.name.c_str());
496+
=======
497+
RCLCPP_DEBUG(logger_, "Published full planning scene: '%s'", msg.name.c_str());
498+
// finish thread on rclcpp shutdown (otherwise rate.sleep() will crash)
499+
if (!rclcpp::ok())
500+
break;
501+
>>>>>>> f4cf780f8 (PSM: finish thread on rclcpp::shutdown (#3484))
495502
rate.sleep();
496503
}
497504
} while (publish_planning_scene_);

0 commit comments

Comments
 (0)