Skip to content

Check rclcpp::ok before sleeping for clean shutdown (backport #3484)#3486

Merged
MarqRazz merged 1 commit intojazzyfrom
mergify/bp/jazzy/pr-3484
May 28, 2025
Merged

Check rclcpp::ok before sleeping for clean shutdown (backport #3484)#3486
MarqRazz merged 1 commit intojazzyfrom
mergify/bp/jazzy/pr-3484

Conversation

@mergify
Copy link
Copy Markdown

@mergify mergify bot commented May 28, 2025

Description

In MTC PR#684 I found move_group fails to shut down cleanly when preempting motion. This is because we are asking the node to sleep when the stack has been requested to shut down. To fix this I added a simple guard to make sure rclcpp::ok() before sleeping.

Here is a snippet of the stack trace when shutting down.

[move_group-5] #10   Source "/root/my_ws/src/moveit2/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp", line 549, in scenePublishingThread [0x7d8db9c1afaf]
[move_group-5]         546:       planning_scene_publisher_->publish(msg);
[move_group-5]         547:       if (is_full)
[move_group-5]         548:         RCLCPP_DEBUG(logger_, "Published full planning scene: '%s'", msg.name.c_str());
[move_group-5]       > 549:       rate.sleep();
[move_group-5]         550:     }
[move_group-5] #9    Object "/opt/ros/jazzy/lib/librclcpp.so", at 0x7d8db914c480, in rclcpp::Rate::sleep()
[move_group-5] #8    Object "/opt/ros/jazzy/lib/librclcpp.so", at 0x7d8db90a0238, in rclcpp::Clock::sleep_for(rclcpp::Duration, std::shared_ptr<rclcpp::Context>)

Checklist

  • Required by CI: Code is auto formatted using clang-format
  • Extend the tutorials / documentation reference
  • Document API changes relevant to the user in the MIGRATION.md notes
  • Create tests, which fail without this PR reference
  • Include a screenshot if changing a GUI
  • While waiting for someone to review your request, please help review another open pull request to support the maintainers

This is an automatic backport of pull request #3484 done by [Mergify](https://mergify.com).

Calling rate.sleep() on shutdown will crash

(cherry picked from commit f4cf780)
@codecov
Copy link
Copy Markdown

codecov bot commented May 28, 2025

Codecov Report

All modified and coverable lines are covered by tests ✅

Project coverage is 46.19%. Comparing base (7853b8c) to head (70ea871).
Report is 1 commits behind head on jazzy.

Additional details and impacted files
@@            Coverage Diff             @@
##            jazzy    #3486      +/-   ##
==========================================
+ Coverage   46.19%   46.19%   +0.01%     
==========================================
  Files         718      718              
  Lines       62667    62669       +2     
  Branches     7587     7589       +2     
==========================================
+ Hits        28942    28943       +1     
- Misses      33560    33562       +2     
+ Partials      165      164       -1     

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

@MarqRazz MarqRazz merged commit 5450b9a into jazzy May 28, 2025
8 checks passed
@MarqRazz MarqRazz deleted the mergify/bp/jazzy/pr-3484 branch May 28, 2025 19:28
@github-project-automation github-project-automation bot moved this to ✅ Done in MoveIt May 28, 2025
valmikikothare added a commit to valmikikothare/moveit2 that referenced this pull request May 28, 2025
PSM: finish thread on rclcpp::shutdown (moveit#3484) (moveit#3486)
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant