File tree 1 file changed +3
-1
lines changed
moveit_planners/pilz_industrial_motion_planner/src
1 file changed +3
-1
lines changed Original file line number Diff line number Diff line change @@ -72,8 +72,10 @@ void MoveGroupSequenceAction::initialize()
72
72
{
73
73
// start the move action server
74
74
RCLCPP_INFO_STREAM (getLogger (), " initialize move group sequence action" );
75
+ // Use MutuallyExclusiveCallbackGroup to prevent race conditions in callbacks.
76
+ // See: https://github.com/moveit/moveit2/issues/3117 for details.
75
77
action_callback_group_ =
76
- context_->moveit_cpp_ ->getNode ()->create_callback_group (rclcpp::CallbackGroupType::Reentrant );
78
+ context_->moveit_cpp_ ->getNode ()->create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive );
77
79
move_action_server_ = rclcpp_action::create_server<moveit_msgs::action::MoveGroupSequence>(
78
80
context_->moveit_cpp_ ->getNode (), " sequence_move_group" ,
79
81
[](const rclcpp_action::GoalUUID& /* unused */ ,
You can’t perform that action at this time.
0 commit comments