ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Here is the solution proposed by @codebot to call a service from the callback of a sub : https://github.com/codebot/ros2_patterns/blob/master/sub_calling_service.py
Here is what he said about the solution though :
The key issue is that calling a service synchronously from within a subscriber callback is usually not a good design, because it's possible that the inbound messages will be coming more quickly than the service can process them, which could result in an uncontrolled message queue forming. The general pattern is that topic callbacks should be "fast".
Anyway, if you still want to try :
To accomplish this in rclpy, we can asynchronously issue the service request. Then in the main
spin()
loop, we can look at the array of futures and, whenever one is completed, we can read its result.So the way I threw that together will also result in an unbounded request queue if the inbound message stream is coming really fast and the service is slow but you could control that by looking at the length of
self.client_futures
and not adding to it if it's already larger than some threshold.
#!/usr/bin/env python3
import sys
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from test_msgs.srv import Empty
class SubscriberClientAsync(Node):
def __init__(self):
super().__init__('sub_client_node')
self.client = self.create_client(Empty, 'service')
self.sub = self.create_subscription(String, 'topic', self.topic_cb)
self.client_futures = []
def topic_cb(self, msg):
print("sub_cb({})".format(msg.data))
self.client_futures.append(self.client.call_async(Empty.Request()))
def spin(self):
while rclpy.ok():
rclpy.spin_once(self)
incomplete_futures = []
for f in self.client_futures:
if f.done():
res = f.result()
print("received service result: {}".format(res))
else:
incomplete_futures.append(f)
self.client_futures = incomplete_futures
if __name__ == '__main__':
rclpy.init()
node = SubscriberClientAsync()
node.spin()