Skip to content

Implement realtime-safe stall detection for parallel gripper controller #1855

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 3 commits into
base: master
Choose a base branch
from

Conversation

ashwinsushil
Copy link

Convert last_movement_time_ from direct rclcpp::Time to RealtimeThreadSafeBox to ensure thread-safe communication between realtime and non-realtime contexts.

Changes:

  • Replace rclcpp::Time last_movement_time_ with RealtimeThreadSafeBoxrclcpp::Time
  • Initialize RealtimeThreadSafeBox in on_activate() method

Fixes potential realtime violations in gripper stall timeout mechanism.

closes #1853

Convert last_movement_time_ from direct rclcpp::Time to RealtimeThreadSafeBox
to ensure thread-safe communication between realtime and non-realtime contexts.

Changes:
- Replace rclcpp::Time last_movement_time_ with RealtimeThreadSafeBox<rclcpp::Time>
- Initialize RealtimeThreadSafeBox in on_activate() method

Fixes potential realtime violations in gripper stall timeout mechanism.
@ashwinsushil ashwinsushil marked this pull request as draft August 7, 2025 07:53
@ashwinsushil ashwinsushil marked this pull request as ready for review August 7, 2025 07:55
Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for working on this, some comments below

Copy link

codecov bot commented Aug 7, 2025

Codecov Report

❌ Patch coverage is 4.76190% with 20 lines in your changes missing coverage. Please review.
✅ Project coverage is 85.97%. Comparing base (a01fd0b) to head (c373c15).

Files with missing lines Patch % Lines
...roller/parallel_gripper_action_controller_impl.hpp 4.76% 20 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##           master    #1855      +/-   ##
==========================================
- Coverage   85.98%   85.97%   -0.02%     
==========================================
  Files         129      129              
  Lines       13112    13116       +4     
  Branches     1144     1144              
==========================================
+ Hits        11275    11276       +1     
- Misses       1469     1472       +3     
  Partials      368      368              
Flag Coverage Δ
unittests 85.97% <4.76%> (-0.02%) ⬇️

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
...roller/parallel_gripper_action_controller_impl.hpp 25.61% <4.76%> (-0.02%) ⬇️
🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Ashwin Sushil added 2 commits August 7, 2025 12:52
Replace blocking set() with non-blocking try_set() for last_movement_time_
initialization in on_activate() method, as this lifecycle callback can be
executed from the realtime thread in some ROS2 control implementations.
Use try_get/try_set for rt_active_goal_ operations in check_for_success()
since this method runs in the realtime control loop. Prevents potential
blocking during goal completion and stall detection.
Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

Copy link
Member

@saikishor saikishor left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Rest looks good to me

@@ -378,6 +385,8 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
pre_alloc_result_->reached_goal = false;
pre_alloc_result_->stalled = false;

last_movement_time_.try_set(rclcpp::Time(0, 0, RCL_ROS_TIME));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
last_movement_time_.try_set(rclcpp::Time(0, 0, RCL_ROS_TIME));
last_movement_time_.try_set(rclcpp::Time(0, 0, RCL_CLOCK_UNINITIALIZED));

Sorry, it's just this one. Initializing with ROS time is still a valid time, better set an invalid type

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@saikishor Of course! No worries. I'll commit this suggestion real quick.

May I ask what’s the main reason for this change? You don’t want the time to be valid in on_activate()? It doesn’t really matter here since in accepted_callback() we set it with last_movement_time_.set(get_node()->now());.

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.

Potential realtime thread safety violations in parallel gripper action controller
3 participants