From 6d3794d154a4f5de81a8a0bd4451f3de2b49ce41 Mon Sep 17 00:00:00 2001 From: Pimpest <82343504+pimpest@users.noreply.github.com> Date: Mon, 13 Apr 2026 14:28:08 +0200 Subject: [PATCH] Made interaction node use multitreaded executor --- toid_interaction/package.xml | 1 + .../toid_interaction/interaction_node.py | 14 ++++++++------ 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/toid_interaction/package.xml b/toid_interaction/package.xml index 6fde46c..d48ec2b 100644 --- a/toid_interaction/package.xml +++ b/toid_interaction/package.xml @@ -14,6 +14,7 @@ python3-serial python3-gpiozero + toid_msgs ament_python diff --git a/toid_interaction/toid_interaction/interaction_node.py b/toid_interaction/toid_interaction/interaction_node.py index b887c9a..842736e 100644 --- a/toid_interaction/toid_interaction/interaction_node.py +++ b/toid_interaction/toid_interaction/interaction_node.py @@ -1,4 +1,6 @@ import rclpy +import rclpy.callback_groups +import rclpy.executors from rclpy.node import Node from std_srvs.srv import Empty @@ -14,7 +16,6 @@ from toid_msgs.srv import SendString from rclpy.action.server import ServerGoalHandle from rclpy.action.server import ActionServer -import asyncio class InteracitionNode(Node): @@ -41,8 +42,10 @@ class InteracitionNode(Node): self.output_pin_ = OutputDevice(27) self.start_pin_action_ = ActionServer( - self, EmptyAction, "/start_plug", execute_callback=self.start_plug_action_cb + self, EmptyAction, "/start_plug", execute_callback=self.start_plug_action_cb, + callback_group=rclpy.callback_groups.ReentrantCallbackGroup() ) + self.get_logger().info("Action 'start_plug' ready.") @@ -93,9 +96,9 @@ class InteracitionNode(Node): async def start_plug_action_cb(self, goal_handle: ServerGoalHandle): while not self.btn_.is_active: - await asyncio.sleep(0.1) + pass while self.btn_.is_active: - await asyncio.sleep(0.1) + pass goal_handle.succeed() return EmptyAction.Result() @@ -104,8 +107,7 @@ def main(args=None): rclpy.init(args=args) node = InteracitionNode() - rclpy.spin(node) - + rclpy.executors.MultiThreadedExecutor().spin(node) rclpy.shutdown()