Skip to content

Commit

Permalink
Fix: Resolve race condition in MoveGroupSequenceAction (#3125)
Browse files Browse the repository at this point in the history
(cherry picked from commit 6d94dfb)

# Conflicts:
#	moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp
  • Loading branch information
maxwelllls authored and mergify[bot] committed Nov 22, 2024
1 parent 172c128 commit 03caacc
Showing 1 changed file with 7 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,15 @@ MoveGroupSequenceAction::MoveGroupSequenceAction()
void MoveGroupSequenceAction::initialize()
{
// start the move action server
<<<<<<< HEAD
RCLCPP_INFO_STREAM(LOGGER, "initialize move group sequence action");
=======
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.
>>>>>>> 6d94dfb71 (Fix: Resolve race condition in MoveGroupSequenceAction (#3125))
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 03caacc

Please sign in to comment.