Skip to content

Commit 55383ae

Browse files
authored
Revamp the simple client tutorial to split the spin into main. (ros2#4538)
That way it is clearer that spin is a concept that is program wide, not just in the Node class. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 4a50302 commit 55383ae

File tree

1 file changed

+10
-10
lines changed

1 file changed

+10
-10
lines changed

source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Service-And-Client.rst

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -196,16 +196,16 @@ Inside the ``ros2_ws/src/py_srvcli/py_srvcli`` directory, create a new file call
196196
def send_request(self, a, b):
197197
self.req.a = a
198198
self.req.b = b
199-
self.future = self.cli.call_async(self.req)
200-
rclpy.spin_until_future_complete(self, self.future)
201-
return self.future.result()
199+
return self.cli.call_async(self.req)
202200
203201
204202
def main():
205203
rclpy.init()
206204
207205
minimal_client = MinimalClientAsync()
208-
response = minimal_client.send_request(int(sys.argv[1]), int(sys.argv[2]))
206+
future = minimal_client.send_request(int(sys.argv[1]), int(sys.argv[2]))
207+
rclpy.spin_until_future_complete(minimal_client, future)
208+
response = future.result()
209209
minimal_client.get_logger().info(
210210
'Result of add_two_ints: for %d + %d = %d' %
211211
(int(sys.argv[1]), int(sys.argv[2]), response.sum))
@@ -246,26 +246,26 @@ Finally it creates a new ``AddTwoInts`` request object.
246246
self.get_logger().info('service not available, waiting again...')
247247
self.req = AddTwoInts.Request()
248248
249-
Below the constructor is the ``send_request`` method, which will send the request and spin until it receives the response or fails.
249+
Below the constructor is the ``send_request`` method, which will send the request and return a future that can be passed to ``spin_until_future_complete``:
250250

251251
.. code-block:: python
252252
253253
def send_request(self, a, b):
254254
self.req.a = a
255255
self.req.b = b
256-
self.future = self.cli.call_async(self.req)
257-
rclpy.spin_until_future_complete(self, self.future)
258-
return self.future.result()
256+
return self.cli.call_async(self.req)
259257
260-
Finally we have the ``main`` method, which constructs a ``MinimalClientAsync`` object, sends the request using the passed-in command-line arguments, and logs the results.
258+
Finally we have the ``main`` method, which constructs a ``MinimalClientAsync`` object, sends the request using the passed-in command-line arguments, calls ``spin_until_future_complete``, and logs the results:
261259

262260
.. code-block:: python
263261
264262
def main():
265263
rclpy.init()
266264
267265
minimal_client = MinimalClientAsync()
268-
response = minimal_client.send_request(int(sys.argv[1]), int(sys.argv[2]))
266+
future = minimal_client.send_request(int(sys.argv[1]), int(sys.argv[2]))
267+
rclpy.spin_until_future_complete(minimal_client, future)
268+
response = future.result()
269269
minimal_client.get_logger().info(
270270
'Result of add_two_ints: for %d + %d = %d' %
271271
(int(sys.argv[1]), int(sys.argv[2]), response.sum))

0 commit comments

Comments
 (0)