2727from rclpy .qos import QoSProfile
2828from rclpy .qos import QoSReliabilityPolicy as Reliability
2929
30- from rmf_task_msgs .msg import ApiRequest
30+ from rmf_task_msgs .msg import ApiRequest , ApiResponse
3131
3232###############################################################################
3333
@@ -61,6 +61,16 @@ def __init__(self, argv=sys.argv):
6161 ApiRequest , 'task_api_requests' , transient_qos
6262 )
6363
64+ self .response = rclpy .Future ()
65+
66+ def receive_response (response_msg : ApiResponse ):
67+ if response_msg .request_id == msg .request_id :
68+ self .response .set_result (json .loads (response_msg .json_msg ))
69+
70+ self .sub = self .create_subscription (
71+ ApiResponse , 'task_api_responses' , receive_response , transient_qos
72+ )
73+
6474 # Construct task
6575 msg = ApiRequest ()
6676 msg .request_id = 'cancel_task_' + str (uuid .uuid4 ())
@@ -82,7 +92,13 @@ def main(argv=sys.argv):
8292 args_without_ros = rclpy .utilities .remove_ros_args (sys .argv )
8393
8494 task_requester = TaskRequester (args_without_ros )
85- rclpy .spin_once (task_requester )
95+ rclpy .spin_until_future_complete (
96+ task_requester , task_requester .response , timeout_sec = 5.0
97+ )
98+ if task_requester .response .done ():
99+ print (f'Got response: \n { task_requester .response .result ()} ' )
100+ else :
101+ print ('Did not get a response' )
86102 rclpy .shutdown ()
87103
88104
0 commit comments