Made interaction node use multitreaded executor

This commit is contained in:
2026-04-13 14:28:08 +02:00
parent 4c29baa005
commit 6d3794d154
2 changed files with 9 additions and 6 deletions

View File

@@ -14,6 +14,7 @@
<depend>python3-serial</depend> <depend>python3-serial</depend>
<depend>python3-gpiozero</depend> <depend>python3-gpiozero</depend>
<depend>toid_msgs</depend>
<export> <export>
<build_type>ament_python</build_type> <build_type>ament_python</build_type>

View File

@@ -1,4 +1,6 @@
import rclpy import rclpy
import rclpy.callback_groups
import rclpy.executors
from rclpy.node import Node from rclpy.node import Node
from std_srvs.srv import Empty 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 ServerGoalHandle
from rclpy.action.server import ActionServer from rclpy.action.server import ActionServer
import asyncio
class InteracitionNode(Node): class InteracitionNode(Node):
@@ -41,8 +42,10 @@ class InteracitionNode(Node):
self.output_pin_ = OutputDevice(27) self.output_pin_ = OutputDevice(27)
self.start_pin_action_ = ActionServer( 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.") 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): async def start_plug_action_cb(self, goal_handle: ServerGoalHandle):
while not self.btn_.is_active: while not self.btn_.is_active:
await asyncio.sleep(0.1) pass
while self.btn_.is_active: while self.btn_.is_active:
await asyncio.sleep(0.1) pass
goal_handle.succeed() goal_handle.succeed()
return EmptyAction.Result() return EmptyAction.Result()
@@ -104,8 +107,7 @@ def main(args=None):
rclpy.init(args=args) rclpy.init(args=args)
node = InteracitionNode() node = InteracitionNode()
rclpy.spin(node) rclpy.executors.MultiThreadedExecutor().spin(node)
rclpy.shutdown() rclpy.shutdown()