Skip to content

Commit

Permalink
Fix: Resolve race condition in MoveGroupSequenceAction
Browse files Browse the repository at this point in the history
Replaced `ReentrantCallbackGroup` with `MutuallyExclusiveCallbackGroup` in
`MoveGroupSequenceAction::initialize` to prevent race conditions during stress testing.

This change ensures sequential execution of callbacks, avoiding issues
caused by concurrent execution.

Reference: #3117
  • Loading branch information
maxwelllls committed Nov 22, 2024
1 parent 6487249 commit 9da70e4
Showing 1 changed file with 3 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,10 @@ void MoveGroupSequenceAction::initialize()
{
// start the move action server
RCLCPP_INFO_STREAM(getLogger(), "initialize move group sequence action");
// Use MutuallyExclusiveCallbackGroup to prevent race conditions in callbacks.
// See: https://github.com/moveit/moveit2/issues/3117 for details.
action_callback_group_ =
context_->moveit_cpp_->getNode()->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
context_->moveit_cpp_->getNode()->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
move_action_server_ = rclcpp_action::create_server<moveit_msgs::action::MoveGroupSequence>(
context_->moveit_cpp_->getNode(), "sequence_move_group",
[](const rclcpp_action::GoalUUID& /* unused */,
Expand Down

0 comments on commit 9da70e4

Please sign in to comment.