|
1 | 1 | #!/usr/bin python3
|
2 |
| -from argparse import Action |
3 | 2 | import rclpy
|
| 3 | +from rclpy.node import Node |
4 | 4 | from rclpy.action import ActionClient
|
5 | 5 | from lasr_speech_recognition_interfaces.srv import TranscribeAudio # type: ignore
|
6 | 6 | from lasr_speech_recognition_interfaces.action import TranscribeSpeech
|
7 | 7 |
|
8 |
| -# TODO port file: action client |
| 8 | +# https://docs.ros2.org/latest/api/rclpy/api/actions.html |
9 | 9 |
|
10 |
| -class TestSpeechServerClient: |
| 10 | +class TestSpeechServerClient(Node): |
11 | 11 | def __init__(self):
|
12 |
| - self.node = rclpy.create_node("test_speech_server") |
13 |
| - self.client = ActionClient(self.node, TranscribeSpeech, "transcribe_speech") |
| 12 | + Node.__init__(self, "listen_action_client") |
14 | 13 |
|
15 |
| - def send_goal(self, msg): |
16 |
| - goal = TranscribeSpeech.Goal() |
17 |
| - goal.msg = msg |
| 14 | + self.client = ActionClient(self, TranscribeSpeech, "transcribe_speech") |
| 15 | + self.goal_future = None |
| 16 | + self.result_future = None |
18 | 17 |
|
| 18 | + def send_goal(self, goal): |
| 19 | + self.get_logger().info("Waiting for Whisper server...") |
19 | 20 | self.client.wait_for_server()
|
20 |
| - self.client.send_goal(goal) # should be future and async? |
| 21 | + self.get_logger().info("Server activated, sending goal...") |
| 22 | + |
| 23 | + self.goal_future = self.client.send_goal_async(goal, feedback_callback=self.feedback_cb) # Returns a Future instance when the goal request has been accepted or rejected. |
| 24 | + self.goal_future.add_done_callback(self.response_cb) # When received get response |
| 25 | + |
| 26 | + def feedback_cb(self, msg): |
| 27 | + self.get_logger().info(f"Received feedback: {msg.feedback}") |
21 | 28 |
|
22 |
| - # TODO add callback with future and handle result |
| 29 | + def response_cb(self, future): |
| 30 | + handle = future.result() |
| 31 | + if not handle.accepted: |
| 32 | + self.get_logger().info("Goal was rejected") |
| 33 | + return |
23 | 34 |
|
24 |
| -# client.wait_for_server() |
25 |
| -# node.get_logger().info("Done waiting") |
| 35 | + self.get_logger().info("Goal was accepted") |
| 36 | + self.result_future = handle.get_result_async() # Not using get_result() in cb, as can cause deadlock according to docs |
| 37 | + self.result_future.add_done_callback(self.result_cb) |
26 | 38 |
|
27 |
| -def main(): |
| 39 | + def result_cb(self, future): |
| 40 | + result = future.result().result |
| 41 | + self.get_logger().info(f"Transcribed Speech: {result.sequence}") |
| 42 | + |
| 43 | +def main(args=None): |
| 44 | + rclpy.init(args=args) |
28 | 45 | while rclpy.ok():
|
29 |
| - rclpy.init() |
30 |
| - # goal = TranscribeSpeech.Goal() |
31 |
| - # client.send_goal(goal) |
| 46 | + goal = TranscribeSpeech.Goal() |
32 | 47 | client = TestSpeechServerClient()
|
33 |
| - client.send_goal(10) |
34 |
| - rclpy.spin(client.node) |
35 |
| - # client.wait_for_result() |
36 |
| - # result = client.get_result() |
37 |
| - # text = result.sequence |
38 |
| - text = "" |
39 |
| - print(f"Transcribed Speech: {text}") |
40 |
| - |
41 |
| -if __name__ == '__main__': |
| 48 | + try: |
| 49 | + client.send_goal(goal) |
| 50 | + rclpy.spin(client) |
| 51 | + except KeyboardInterrupt: |
| 52 | + client.get_logger().info("Shutting down...") |
| 53 | + finally: |
| 54 | + client.destroy_node() |
| 55 | + rclpy.shutdown() |
| 56 | + |
| 57 | +if __name__ == "__main__": |
42 | 58 | main()
|
0 commit comments