00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 PKG = 'test_rospy'
00040 import roslib; roslib.load_manifest(PKG)
00041
00042 import sys, time
00043 import unittest
00044
00045 import rospy, rostest
00046 from test_rospy.srv import *
00047
00048 SERVICE_BEFORE = 'service_order_before'
00049 SERVICE_AFTER = 'service_order_after'
00050
00051 FAKE_SECRET = 123456
00052
00053 WAIT_TIMEOUT = 10.0
00054
00055 def handle_empty_req(req):
00056 print "Returning fake_secret"
00057 return EmptyReqSrvResponse(FAKE_SECRET)
00058
00059 def service_before():
00060 s = rospy.Service(SERVICE_BEFORE, EmptyReqSrv, handle_empty_req)
00061 rospy.init_node('service_before')
00062 rospy.spin()
00063
00064
00065 def service_after():
00066 rospy.init_node('service_after')
00067 s = rospy.Service(SERVICE_AFTER, EmptyReqSrv, handle_empty_req)
00068 rospy.spin()
00069
00070 class TestServiceOrder(unittest.TestCase):
00071
00072 def _test(self, name, srv, req):
00073 rospy.wait_for_service(name, WAIT_TIMEOUT)
00074 s = rospy.ServiceProxy(name, srv)
00075 resp = s.call(req)
00076 self.assert_(resp is not None)
00077 return resp
00078 def test_before(self):
00079 resp = self._test(SERVICE_BEFORE, EmptyReqSrv,
00080 EmptyReqSrvRequest())
00081 self.assertEquals(FAKE_SECRET, resp.fake_secret,
00082 "fake_secret fields is not set as expected")
00083 def test_after(self):
00084 resp = self._test(SERVICE_AFTER, EmptyReqSrv,
00085 EmptyReqSrvRequest())
00086 self.assertEquals(FAKE_SECRET, resp.fake_secret,
00087 "fake_secret fields is not set as expected")
00088
00089 if __name__ == '__main__':
00090 if '--before' in sys.argv:
00091 service_before()
00092 elif '--after' in sys.argv:
00093 service_after()
00094 else:
00095 rostest.run(PKG, 'rospy_service_decl_order', TestServiceOrder, sys.argv)