## For instruction on writing tutorials
## http://www.ros.org/wiki/WritingTutorials
####################################
##FILL ME IN
####################################
## for a custom note with links:
## note =
## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links 
## note.0= [[rocon_python_comms/Tutorials/indigo/Writing a ServicePair Server (Python)|Writing a ServicePair Server (Python)]]
## descriptive title for the tutorial
## title = Writing a ServicePair Client (Python)
## multi-line description to be displayed in search 
## description = Simple example of a service pair client in python.
## the next tutorial description (optional)
## next =
## links to next tutorial (optional)
## next.0.link=
## next.1.link=
## what level user is this tutorial for 
## level= IntermediateCategory
## keywords = servicepair, rocon
####################################

<<IncludeCSTemplate(TutorialCSHeaderTemplate)>>

<<TableOfContents(4)>>

== Overview ==

This tutorial demonstrates how to write a service pair client in python. Refer to the [[http://docs.ros.org/indigo/api/rocon_python_comms/html/modules.html#module-rocon_python_comms.service_pair_client|sphinx code docs]] for a more detailed reference.

== Non-Blocking Calls ==

{{{#!highlight python
#!/usr/bin/env python

import rospy
from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair
from rocon_python_comms import ServicePairClient
import unique_id

class ChatterClient(object):

    def __init__(self):
        self.response = None
        self.client = ServicePairClient('chatter', ChatterPair)
        self.client.wait_for_service(rospy.Duration(3.0)) # should catch some exceptions here in case of timeouts
        self.request_id = self.client(ChatterRequest("Hello dude"), timeout=rospy.Duration(3.0), callback=self.callback) 
        rospy.loginfo("Request id %s" % unique_id.toHexString(self.request_id))
        if self.response is not None:
            print("Response %s" % self.response)

    def callback(self, request_id, msg):
        # ideally you'd check request_id against self.request_id
        self.response = msg
        rospy.loginfo("Got the response: %s" % msg)

if __name__ == '__main__':
    rospy.init_node('chatter_client', anonymous=True)
    chatter_client = ChatterClient()
    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:

{{{#!highlight python
#!/usr/bin/env python

import rospy
from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair
from rocon_python_comms import ServicePairClient
import unique_id

class ChatterClient(object):

    def __init__(self):
        self.response = None
        self.client = ServicePairClient('chatter', ChatterPair)
        self.client.wait_for_service(rospy.Duration(3.0)) # should catch some exceptions here in case of timeouts
        self.response = self.client(ChatterRequest("Hello dude"), timeout=rospy.Duration(3.0)) 
        if self.response is not None:
            print("Response %s" % self.response)

if __name__ == '__main__':
    rospy.init_node('chatter_client', anonymous=True)
    chatter_client = ChatterClient()
    rospy.spin()
}}}


## AUTOGENERATED DO NOT DELETE 
## TutorialCategory
## FILL IN THE STACK TUTORIAL CATEGORY HERE