Skip to content

Commit 4482710

Browse files
committed
Finish future callbacks for Action client
1 parent 36cebad commit 4482710

File tree

2 files changed

+42
-26
lines changed

2 files changed

+42
-26
lines changed

common/speech/lasr_speech_recognition_whisper/lasr_speech_recognition_whisper/transcribe_microphone_server.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -189,7 +189,7 @@ async def execute_cb(self, goal_handle) -> None:
189189
goal = goal_handle.request
190190

191191
self.get_logger().info("Request Received")
192-
if goal_handle.is_cancel_requested():
192+
if goal_handle.is_cancel_requested:
193193
return
194194

195195
if goal.energy_threshold > 0.0 and goal.max_phrase_limit > 0.0:
Lines changed: 41 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,42 +1,58 @@
11
#!/usr/bin python3
2-
from argparse import Action
32
import rclpy
3+
from rclpy.node import Node
44
from rclpy.action import ActionClient
55
from lasr_speech_recognition_interfaces.srv import TranscribeAudio # type: ignore
66
from lasr_speech_recognition_interfaces.action import TranscribeSpeech
77

8-
# TODO port file: action client
8+
# https://docs.ros2.org/latest/api/rclpy/api/actions.html
99

10-
class TestSpeechServerClient:
10+
class TestSpeechServerClient(Node):
1111
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")
1413

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
1817

18+
def send_goal(self, goal):
19+
self.get_logger().info("Waiting for Whisper server...")
1920
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}")
2128

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
2334

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)
2638

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)
2845
while rclpy.ok():
29-
rclpy.init()
30-
# goal = TranscribeSpeech.Goal()
31-
# client.send_goal(goal)
46+
goal = TranscribeSpeech.Goal()
3247
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__":
4258
main()

0 commit comments

Comments
 (0)