Skip to content

Commit

Permalink
move_group_interface: No need to spin after publishing (backport #1250)…
Browse files Browse the repository at this point in the history
… (#1500)

(cherry picked from commit 5a39a7f)

Co-authored-by: Jafar <cafer.abdi@gmail.com>
  • Loading branch information
mergify[bot] and JafarAbdi committed Aug 10, 2022
1 parent 540bc65 commit 722c869
Showing 1 changed file with 0 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1006,7 +1006,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
std_msgs::msg::String event;
event.data = "stop";
trajectory_event_publisher_->publish(event);
rclcpp::spin_some(pnode_);
}
}

Expand All @@ -1033,7 +1032,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
aco.touch_links = touch_links;
aco.object.operation = moveit_msgs::msg::CollisionObject::ADD;
attached_object_publisher_->publish(aco);
rclcpp::spin_some(pnode_);
return true;
}

Expand All @@ -1054,13 +1052,11 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
{
aco.link_name = lname;
attached_object_publisher_->publish(aco);
rclcpp::spin_some(pnode_);
}
}
else
{
attached_object_publisher_->publish(aco);
rclcpp::spin_some(pnode_);
}
return true;
}
Expand Down

0 comments on commit 722c869

Please sign in to comment.