Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 2 additions & 6 deletions rclpy/services/minimal_client/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
9 changes: 3 additions & 6 deletions rclpy/services/minimal_client/client_async.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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):
Expand Down