Skip to content

Commit

Permalink
Fix: Resolve race condition in MoveGroupSequenceAction (backport #3125)…
Browse files Browse the repository at this point in the history
… (#3127)
  • Loading branch information
mergify[bot] authored Nov 22, 2024
1 parent 92e8808 commit ed38b2d
Showing 1 changed file with 3 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,10 @@ void MoveGroupSequenceAction::initialize()
{
// start the move action server
RCLCPP_INFO_STREAM(LOGGER, "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 ed38b2d

Please sign in to comment.