Skip to content

Instantly share code, notes, and snippets.

@PeterMitrano
Created November 11, 2025 07:24
Show Gist options
  • Select an option

  • Save PeterMitrano/04226bc6015fee0ee5c7f8781f932022 to your computer and use it in GitHub Desktop.

Select an option

Save PeterMitrano/04226bc6015fee0ee5c7f8781f932022 to your computer and use it in GitHub Desktop.
Simple example of using service callbacks
import threading
from time import sleep
import rclpy
from rclpy.node import Node
from example_interfaces.srv import AddTwoInts
class MinimalClientAsync(Node):
def __init__(self):
super().__init__('minimal_client_async')
self.cli = self.create_client(AddTwoInts, 'add_two_ints')
while not self.cli.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = AddTwoInts.Request()
def send_request(self):
self.req.a = 41
self.req.b = 1
return self.cli.call_async(self.req)
def main(args=None):
rclpy.init(args=args)
minimal_client = MinimalClientAsync()
def _spin_ros():
rclpy.spin(minimal_client)
spin_thread = threading.Thread(target=_spin_ros)
spin_thread.start()
# sleep is not needed, just to demonstrate the separation of the spinning and the service call
sleep(1)
future = minimal_client.send_request()
def _on_result(future):
response = future.result()
minimal_client.get_logger().info(
f'Result of add_two_ints: for {minimal_client.req.a} + {minimal_client.req.b} = {response.sum}')
future.add_done_callback(_on_result)
# This is also not strictly needed, just to keep the main thread alive while waiting for the service response.
while not future.done():
sleep(0.1)
minimal_client.destroy_node()
rclpy.shutdown()
spin_thread.join()
if __name__ == '__main__':
main()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment