diff --git a/rclpy/services/minimal_client/client.py b/rclpy/services/minimal_client/client.py index b2b5f677..1f672ba5 100644 --- a/rclpy/services/minimal_client/client.py +++ b/rclpy/services/minimal_client/client.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import time - from example_interfaces.srv import AddTwoInts import rclpy @@ -27,10 +25,8 @@ def main(args=None): req = AddTwoInts.Request() req.a = 41 req.b = 1 - # TODO(mikaelarguedas) remove this once wait for service implemented - # wait for connection to be established - # (no wait for service in Python yet) - time.sleep(1) + while not cli.wait_for_service(timeout_sec=1.0): + print('service not available, waiting again...') cli.call(req) # when calling wait for future diff --git a/rclpy/services/minimal_client/client_async.py b/rclpy/services/minimal_client/client_async.py index 35739040..61870c9d 100644 --- a/rclpy/services/minimal_client/client_async.py +++ b/rclpy/services/minimal_client/client_async.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import time - from example_interfaces.srv import AddTwoInts import rclpy @@ -29,10 +27,9 @@ def main(args=None): req = AddTwoInts.Request() req.a = 41 req.b = 1 - # TODO(mikaelarguedas) remove this once wait for service implemented - # wait for connection to be established - # (no wait for service in Python yet) - time.sleep(1) + while not cli.wait_for_service(timeout_sec=1.0): + print('service not available, waiting again...') + cli.call(req) while rclpy.ok(): # TODO(mikaelarguedas) This is not the final API, and this does not scale diff --git a/rclpy/services/minimal_client/client_async_member_function.py b/rclpy/services/minimal_client/client_async_member_function.py index f716e68f..b92dc5c5 100644 --- a/rclpy/services/minimal_client/client_async_member_function.py +++ b/rclpy/services/minimal_client/client_async_member_function.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import time - from example_interfaces.srv import AddTwoInts import rclpy @@ -25,10 +23,8 @@ class MinimalClientAsync(Node): def __init__(self): super().__init__('minimal_client_async') self.cli = self.create_client(AddTwoInts, 'add_two_ints') - # TODO(mikaelarguedas) remove this once wait for service implemented - # wait for connection to be established - # (no wait for service in Python yet) - time.sleep(1) + while not self.cli.wait_for_service(timeout_sec=1.0): + print('service not available, waiting again...') self.req = AddTwoInts.Request() def send_request(self):