Note: This tutorial assumes that you have completed the previous tutorials: Writing a ServicePair Server (Python). |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Writing a ServicePair Client (Python)
Description: Simple example of a service pair client in python.Keywords: servicepair, rocon
Tutorial Level: INTERMEDIATE
Contents
Overview
This tutorial demonstrates how to write a service pair client in python. Refer to the sphinx code docs for a more detailed reference.
Non-Blocking Calls
1 #!/usr/bin/env python
2
3 import rospy
4 from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair
5 from rocon_python_comms import ServicePairClient
6 import unique_id
7
8 class ChatterClient(object):
9
10 def __init__(self):
11 self.response = None
12 self.client = ServicePairClient('chatter', ChatterPair)
13 self.client.wait_for_service(rospy.Duration(3.0)) # should catch some exceptions here in case of timeouts
14 self.request_id = self.client(ChatterRequest("Hello dude"), timeout=rospy.Duration(3.0), callback=self.callback)
15 rospy.loginfo("Request id %s" % unique_id.toHexString(self.request_id))
16 if self.response is not None:
17 print("Response %s" % self.response)
18
19 def callback(self, request_id, msg):
20 # ideally you'd check request_id against self.request_id
21 self.response = msg
22 rospy.loginfo("Got the response: %s" % msg)
23
24 if __name__ == '__main__':
25 rospy.init_node('chatter_client', anonymous=True)
26 chatter_client = ChatterClient()
27 rospy.spin()
There are two important points here:
The timeout instructs the ServicePairClient to stop looking for responses after this time.
The wait_for_service delays until the pub/sub connections are established (stops your publisher's early messages disappearing into the void).
Blocking Calls
Blocking is quite straightforward:
1 #!/usr/bin/env python
2
3 import rospy
4 from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair
5 from rocon_python_comms import ServicePairClient
6 import unique_id
7
8 class ChatterClient(object):
9
10 def __init__(self):
11 self.response = None
12 self.client = ServicePairClient('chatter', ChatterPair)
13 self.client.wait_for_service(rospy.Duration(3.0)) # should catch some exceptions here in case of timeouts
14 self.response = self.client(ChatterRequest("Hello dude"), timeout=rospy.Duration(3.0))
15 if self.response is not None:
16 print("Response %s" % self.response)
17
18 if __name__ == '__main__':
19 rospy.init_node('chatter_client', anonymous=True)
20 chatter_client = ChatterClient()
21 rospy.spin()