master.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Revision $Id: testSlave.py 1100 2008-05-29 20:23:54Z sfkwc $
34 
35 import os
36 import sys
37 import string
38 import time
39 try:
40  from xmlrpc.client import ServerProxy
41 except ImportError:
42  from xmlrpclib import ServerProxy
43 
44 import rospy
45 import rosgraph
46 
47 from rosclient import *
48 
49 NODE_INTEGRATION_NAME = "node_integration_test"
50 
51 _name = None
52 
54 def set_node_name(name):
55  global _name
56  _name = name
57 
58 # Have to try as hard as possible to not use rospy code in testing rospy code, so this is
59 # a reimplementation of the caller ID spec so that NodeApiTestCase knows its name
60 
62  if _name is None:
63  raise Exception("set_node_name has not been called yet")
64  ros_ns = os.environ.get(rosgraph.ROS_NAMESPACE, rosgraph.names.GLOBALNS)
65  return rosgraph.names.ns_join(ros_ns, _name)
66 
68 
69  def __init__(self, *args):
70  super(_MasterTestCase, self).__init__(*args)
71  self.ns = os.environ.get(rosgraph.ROS_NAMESPACE, rosgraph.names.GLOBALNS)
73 
74  def setUp(self):
75  super(_MasterTestCase, self).setUp()
76  self.master_uri = os.environ.get(rosgraph.ROS_MASTER_URI, None)
77  self._checkUri(self.master_uri)
78  self.master = ServerProxy(self.master_uri)
79 
80 
81  def _checkUri(self, uri):
82  try:
83  import urllib.parse as urlparse
84  except ImportError:
85  import urlparse
86  parsed = urlparse.urlparse(uri)
87  self.assertTrue(parsed[0] in ['http', 'https'], 'protocol [%s] in [%s] invalid'%(parsed[0], uri))
88  self.assertTrue(parsed[1], 'host missing [%s]'%uri)
89  if not sys.version.startswith('2.4'): #check not available on py24
90  self.assertTrue(parsed.port, 'port missing/invalid [%s]'%uri)
91 
92 
94 
95 
96  def _testGetMasterUri(self):
97  # test with bad arity
98  self.apiError(self.master.getMasterUri())
99  # test success
100  uri = self.apiSuccess(self.master.getMasterUri(self.caller_id))
101  self._checkUri(uri)
102 
103  # make sure we agree on ports
104  try:
105  import urllib.parse as urlparse
106  except ImportError:
107  import urlparse
108  parsed = urlparse.urlparse(uri)
109  parsed2 = urlparse.urlparse(self.master_uri)
110 
111  self.assertEqual(parsed.port, parsed2.port, "expected ports do not match")
112 
113 
114  def _testGetPid(self):
115  # test with bad arity
116  self.apiError(self.master.getPid())
117  # test success
118  pid = self.apiSuccess(self.master.getPid(self.caller_id))
119  self.assertTrue(pid > 0)
120 
121 
122  def _testGetUri(self):
123  # test with bad arity
124  self.apiError(self.master.getUri())
125  # test success
126  uri = self.apiSuccess(self.master.getUri(self.caller_id))
127  self.assertTrue(type(uri) == str)
128 
129 
131  master = self.master
132 
133  caller_id = '/service_node'
134  caller_api = 'http://localhost:4567/'
135  service_base = '/service'
136 
137  # test success
138  for i in range(0, 10):
139  service_name = "%s-%s"%(service_base, i)
140  service_api = 'rosrpc://localhost:123%s/'%i
141  # register the service
142  self.apiSuccess(master.registerService(caller_id, service_name, service_api, caller_api))
143  # test master state
144  val = self.apiSuccess(master.lookupService(caller_id, service_name))
145  self.assertEqual(service_api, val)
146  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
147  self.assertEqual(caller_api, val)
148 
149  _, _, srvs = self.apiSuccess(master.getSystemState(self.caller_id))
150  for j in range(0, i+1):
151  jservice_name = "%s-%s"%(service_base, j)
152  jentry = [jservice_name, [caller_id]]
153  self.assertTrue(jentry in srvs, "master service list %s is missing %s"%(srvs, jentry))
154 
155  # TODO: have to test subscriber callback
156  # TODO: validate with getSystemState()
157 
158 
161 
164  master = self.master
165  caller_id = '/service_node'
166  caller_api = 'http://localhost:4567/'
167  service_base = '/service'
168 
169  for i in range(0, 10):
170  service_name = "%s-%s"%(service_base, i)
171  service_api = 'rosrpc://localhost:123%s/'%i
172 
173  # unregister the service
174  code, msg, val = master.unregisterService(caller_id, service_name, service_api)
175  self.assertEqual(code, 1, "code != 1, return message was [%s]"%msg)
176 
177  # test the master state
178  self.apiError(master.lookupService(self.caller_id, service_name), "master has a reference to unregistered service. message from master for unregister was [%s]"%msg)
179 
180  if i < 9:
181  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
182  self.assertEqual(caller_api, val, "master prematurely invalidated node entry for [%s] (lookupNode)"%caller_id)
183 
184  _, _, srvs = self.apiSuccess(master.getSystemState(self.caller_id))
185  for j in range(0, i+1):
186  jservice_name = "%s-%s"%(service_base, j)
187  jentry = [jservice_name, [caller_id]]
188  self.assertTrue(jentry not in srvs, "master service list %s should not have %s"%(srvs, jentry))
189  for j in range(i+1, 10):
190  jservice_name = "%s-%s"%(service_base, j)
191  jentry = [jservice_name, [caller_id]]
192  self.assertTrue(jentry in srvs, "master service list %s is missing %s"%(srvs, jentry))
193 
194  # TODO: have to test subscriber callback
195 
196  # Master's state should be zero'd out now
197 
198  # - #457 make sure that lookupNode isn't returning stale info
199  self.apiError(master.lookupNode(self.caller_id, caller_id), "master has a stale reference to unregistered service node API")
200  _, _, srvs = self.apiSuccess(master.getSystemState(self.caller_id))
201  srvs = [s for s in srvs if not s[0].startswith('/rosout/') and not s[0].endswith('/get_loggers') and not s[0].endswith('/set_logger_level')]
202  self.assertEqual(0, len(srvs), "all services should have been unregistered: %s"%srvs)
203 
205  master = self.master
206 
207  service = '/service'
208  service_api = 'rosrpc://localhost:1234/'
209  caller_api = 'http://localhost:4567/'
210 
211  # test with bad arity
212  self.apiError(master.registerService())
213  self.apiError(master.registerService(self.caller_id, service))
214  self.apiError(master.registerService(self.caller_id, service, service_api))
215 
216  # test with bad args
217  self.apiError(master.registerService(self.caller_id, '', service_api, caller_api))
218  self.apiError(master.registerService(self.caller_id, service, '', caller_api))
219  self.apiError(master.registerService(self.caller_id, service, service_api, ''))
220 
222  master = self.master
223 
224  service = '/service'
225  service_api = 'rosrpc://localhost:1234/'
226 
227  # test with bad arity
228  self.apiError(master.unregisterService())
229  self.apiError(master.unregisterService(self.caller_id, service))
230 
231  # test with bad args
232  self.apiError(master.unregisterService(self.caller_id, '', service_api))
233  self.apiError(master.unregisterService(self.caller_id, service, ''))
234 
236  master = self.master
237 
238  topic = '/pub_topic'
239  topic_type = 'test_rosmaster/String'
240  caller_api = 'http://localhost:4567/'
241 
242  # test with bad arity
243  self.apiError(master.registerPublisher())
244  self.apiError(master.registerPublisher(self.caller_id, topic))
245  self.apiError(master.registerPublisher(self.caller_id, topic, topic_type))
246 
247  # test with bad args
248  self.apiError(master.registerPublisher(self.caller_id, '', topic_type, caller_api))
249  self.apiError(master.registerPublisher(self.caller_id, topic, '', caller_api))
250  self.apiError(master.registerPublisher(self.caller_id, topic, topic_type, ''))
251 
253  master = self.master
254 
255  topic = '/pub_topic'
256  caller_api = 'http://localhost:4567/'
257 
258  # test with bad arity
259  self.apiError(master.unregisterPublisher())
260  self.apiError(master.unregisterPublisher(self.caller_id, topic))
261 
262  # test with bad args
263  self.apiError(master.unregisterPublisher(self.caller_id, '', caller_api))
264  self.apiError(master.unregisterPublisher(self.caller_id, topic, ''))
265 
267  master = self.master
268 
269  topic = '/sub_topic'
270  topic_type = 'test_rosmaster/String'
271  caller_api = 'http://localhost:4567/'
272 
273  # test with bad arity
274  self.apiError(master.registerSubscriber())
275  self.apiError(master.registerSubscriber(self.caller_id, topic))
276  self.apiError(master.registerSubscriber(self.caller_id, topic, topic_type))
277 
278  # test with bad args
279  self.apiError(master.registerSubscriber(self.caller_id, '', topic_type, caller_api))
280  self.apiError(master.registerSubscriber(self.caller_id, topic, '', caller_api))
281  self.apiError(master.registerSubscriber(self.caller_id, topic, topic_type, ''))
282 
284  master = self.master
285 
286  topic = '/sub_topic'
287  caller_api = 'http://localhost:4567/'
288 
289  # test with bad arity
290  self.apiError(master.registerSubscriber())
291  self.apiError(master.registerSubscriber(self.caller_id, topic))
292 
293  # test with bad args
294  self.apiError(master.unregisterSubscriber(self.caller_id, '', caller_api))
295  self.apiError(master.unregisterSubscriber(self.caller_id, topic, ''))
296 
297 
299  master = self.master
300 
301  caller_id = '/pub_node'
302  caller_api = 'http://localhost:4567/'
303  topic_base = '/pub_topic'
304  topic_type = 'test_rosmaster/String'
305 
306  # test success
307  for i in range(0, 10):
308  topic_name = "%s-%s"%(topic_base, i)
309  # register the topic
310  self.apiSuccess(master.registerPublisher(caller_id, topic_name, topic_type, caller_api))
311  # test master state
312  # - master knows caller_id
313  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
314  self.assertEqual(caller_api, val)
315  # - master knows topic type
316  val = self.apiSuccess(master.getPublishedTopics(self.caller_id, '/'))
317  self.assertTrue([topic_name, topic_type] in val, "master does not know topic type: %s"%val)
318  # - test new api as well
319  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
320  self.assertTrue([topic_name, topic_type] in val, "master does not know topic type: %s"%val)
321 
322  pubs, _, _ = self.apiSuccess(master.getSystemState(self.caller_id))
323  for j in range(0, i+1):
324  jtopic_name = "%s-%s"%(topic_base, j)
325  jentry = [jtopic_name, [caller_id]]
326  self.assertTrue(jentry in pubs, "master pub/sub list %s is missing %s"%(pubs, jentry))
327 
328  # TODO: have to test subscriber callback
329 
330 
332  master = self.master
333  caller_id = '/pub_node'
334  caller_api = 'http://localhost:4567/'
335  topic_name = '/type_test_pub_topic'
336 
337  # register anytype first
338  val = self.apiSuccess(master.registerPublisher(caller_id, topic_name, '*', caller_api))
339  self.assertEqual([], val) # should report no subscribers
340  val = self.apiSuccess(master.getPublishedTopics(self.caller_id, '/'))
341  self.assertTrue([topic_name, '*'] in val, "master is not reporting * as type: %s"%val)
342  # - test new api as well
343  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
344  self.assertTrue([topic_name, '*'] in val, "master is not reporting * as type: %s"%val)
345 
346  # register a grounded type and make sure that '*' can't overwrite it
347  for t in ['test_rosmaster/String', '*']:
348  val = self.apiSuccess(master.registerPublisher(caller_id, topic_name, t, caller_api))
349  self.assertEqual([], val) # should report no subscribers
350  val = self.apiSuccess(master.getPublishedTopics(self.caller_id, '/'))
351  self.assertTrue([topic_name, 'test_rosmaster/String'] in val, "master is not reporting test_rosmaster/String as type: %s"%val)
352 
353  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
354  self.assertTrue([topic_name, 'test_rosmaster/String'] in val, "master is not reporting test_rosmaster/String as type: %s"%val)
355 
356 
359 
360  # a couple more test cases to verify that registerPublisher's return value is correct
361  master = self.master
362  topic = '/pub_topic-0'
363  type = 'test_rosmaster/String'
364  pub_caller_api = 'http://localhost:4567/'
365 
366  subs = []
367  for i in range(5678, 5685):
368  api = 'http://localhost:%s'%i
369  subs.append(api)
370  self.apiSuccess(master.registerSubscriber('/sub_node-%i'%i, topic, type, api))
371  val = self.apiSuccess(master.registerPublisher('/pub_node', topic, type, pub_caller_api))
372  self.assertEqual(subs, val)
373 
376  master = self.master
377  caller_id = '/pub_node'
378  caller_api = 'http://localhost:4567/'
379  topic_base = '/pub_topic'
380 
381  for i in range(0, 10):
382  topic_name = "%s-%s"%(topic_base, i)
383 
384  # unregister the topic
385  code, msg, val = master.unregisterPublisher(caller_id, topic_name, caller_api)
386  self.assertEqual(code, 1, "code != 1, return message was [%s]"%msg)
387 
388  # test the master state
389  if i < 9:
390  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
391  self.assertEqual(caller_api, val, "master prematurely invalidated node entry for [%s] (lookupNode)"%caller_id)
392 
393  pubs, _, _ = self.apiSuccess(master.getSystemState(self.caller_id))
394  for j in range(0, i+1):
395  jtopic_name = "%s-%s"%(topic_base, j)
396  jentry = [jtopic_name, [caller_id]]
397  self.assertTrue(jentry not in pubs, "master pub/sub list %s should not have %s"%(pubs, jentry))
398  for j in range(i+1, 10):
399  jtopic_name = "%s-%s"%(topic_base, j)
400  jentry = [jtopic_name, [caller_id]]
401  self.assertTrue(jentry in pubs, "master pub/sub list %s is missing %s"%(pubs, jentry))
402 
403  # TODO: have to test subscriber callback
404 
405  # - #457 make sure that lookupNode isn't returning stale info
406  self.apiError(master.lookupNode(self.caller_id, caller_id), "master has a stale reference to unregistered topic node API. pubs are %s"%pubs)
407 
408 
411  master = self.master
412 
413  caller_id = '/sub_node'
414  caller_api = 'http://localhost:4567/'
415  topic_base = '/sub_topic'
416  topic_type = 'test_rosmaster/String'
417 
418  # test success
419  for i in range(0, 10):
420  topic_name = "%s-%s"%(topic_base, i)
421  # register the topic
422  self.apiSuccess(master.registerSubscriber(caller_id, topic_name, topic_type, caller_api))
423  # test master state
424  # - master knows caller_id
425  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
426  self.assertEqual(caller_api, val)
427 
428  # - master should know topic type
429  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
430  self.assertTrue([topic_name, topic_type] in val, "master does not know topic type: %s"%val)
431 
432  _, subs, _ = self.apiSuccess(master.getSystemState(self.caller_id))
433  for j in range(0, i+1):
434  jtopic_name = "%s-%s"%(topic_base, j)
435  jentry = [jtopic_name, [caller_id]]
436  self.assertTrue(jentry in subs, "master pub/sub list %s is missing %s"%(subs, jentry))
437 
438 
441 
444  master = self.master
445  caller_id = '/sub_node'
446  caller_api = 'http://localhost:4567/'
447  topic_base = '/sub_topic'
448 
449  for i in range(0, 10):
450  topic_name = "%s-%s"%(topic_base, i)
451 
452  # unregister the topic
453  code, msg, val = master.unregisterSubscriber(caller_id, topic_name, caller_api)
454  self.assertEqual(code, 1, "code != 1, return message was [%s]"%msg)
455 
456  # test the master state
457  if i < 9:
458  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
459  self.assertEqual(caller_api, val, "master prematurely invalidated node entry for [%s] (lookupNode)"%caller_id)
460 
461  _, subs, _ = self.apiSuccess(master.getSystemState(self.caller_id))
462  for j in range(0, i+1):
463  jtopic_name = "%s-%s"%(topic_base, j)
464  jentry = [jtopic_name, [caller_id]]
465  self.assertTrue(jentry not in subs, "master pub/sub list %s should not have %s"%(subs, jentry))
466  for j in range(i+1, 10):
467  jtopic_name = "%s-%s"%(topic_base, j)
468  jentry = [jtopic_name, [caller_id]]
469  self.assertTrue(jentry in subs, "master pub/sub list %s is missing %s"%(subs, jentry))
470 
471  # - #457 make sure that lookupNode isn't returning stale info
472  self.apiError(master.lookupNode(self.caller_id, caller_id), "master has a stale reference to unregistered topic node API. subs are %s"%subs)
473 
474 
test.master._MasterTestCase.setUp
def setUp(self)
Definition: master.py:74
test.master.MasterApiTestCase._testRegisterServiceInvalid
def _testRegisterServiceInvalid(self)
Definition: master.py:204
test.master._MasterTestCase
Definition: master.py:67
test.master.MasterApiTestCase._testRegisterServiceSuccess
def _testRegisterServiceSuccess(self)
validate master.registerService(caller_id, service, service_api, caller_api)
Definition: master.py:159
test.master._MasterTestCase.master
master
Definition: master.py:78
test.master._MasterTestCase.ns
ns
Definition: master.py:71
test.master.MasterApiTestCase._testUnregisterPublisherSuccess
def _testUnregisterPublisherSuccess(self)
Definition: master.py:374
test.rosclient.TestRosClient
Definition: rosclient.py:44
test.master.MasterApiTestCase._testRegisterPublisherInvalid
def _testRegisterPublisherInvalid(self)
Definition: master.py:235
test.master.MasterApiTestCase._subTestRegisterSubscriberSimpleSuccess
def _subTestRegisterSubscriberSimpleSuccess(self)
common test subroutine of both register and unregister tests.
Definition: master.py:410
test.master.MasterApiTestCase._testGetUri
def _testGetUri(self)
validate master.getUri(caller_id)
Definition: master.py:122
test.master._MasterTestCase._checkUri
def _checkUri(self, uri)
validates a URI as being http(s)
Definition: master.py:81
test.master.MasterApiTestCase._testRegisterSubscriberInvalid
def _testRegisterSubscriberInvalid(self)
Definition: master.py:266
test.rosclient.TestRosClient.apiSuccess
def apiSuccess(self, args)
unit test assertion that fails if status code is not 1 and otherwise returns the value parameter
Definition: rosclient.py:58
test.master.MasterApiTestCase._testUnregisterSubscriberInvalid
def _testUnregisterSubscriberInvalid(self)
Definition: master.py:283
test.master.get_caller_id
def get_caller_id()
reimplementation of caller ID spec separately from rospy
Definition: master.py:61
test.rosclient.TestRosClient.apiError
def apiError(self, args, msg=None)
unit test assertion that fails if status code is not -1 and otherwise returns true
Definition: rosclient.py:74
test.master.MasterApiTestCase._testGetPid
def _testGetPid(self)
validate master.getPid(caller_id)
Definition: master.py:114
test.master.MasterApiTestCase._testGetMasterUri
def _testGetMasterUri(self)
validate master.getMasterUri(caller_id)
Definition: master.py:96
test.master.MasterApiTestCase._subTestRegisterPublisherSuccess
def _subTestRegisterPublisherSuccess(self)
common test subroutine of both register and unregister tests.
Definition: master.py:298
test.master.MasterApiTestCase._testRegisterPublisherSuccess
def _testRegisterPublisherSuccess(self)
validate master.registerPublisher(caller_id, topic, topic_api, caller_api)
Definition: master.py:357
test.master.MasterApiTestCase._testUnregisterSubscriberSuccess
def _testUnregisterSubscriberSuccess(self)
Definition: master.py:442
test.master.MasterApiTestCase._testRegisterPublisherTypes
def _testRegisterPublisherTypes(self)
#591: this test may change if we make registering '*' unsupported
Definition: master.py:331
test.master.set_node_name
def set_node_name(name)
set_node_name() must be called prior to the unit test so that the test harness knows its ROS name.
Definition: master.py:54
test.master._MasterTestCase.__init__
def __init__(self, *args)
Definition: master.py:69
test.master.MasterApiTestCase
Expects a single test node to be running with name 'test_node' and subscribed to 'test_string'.
Definition: master.py:93
test.master.MasterApiTestCase._testRegisterSubscriberSimpleSuccess
def _testRegisterSubscriberSimpleSuccess(self)
validate master.registerSubscriber(caller_id, topic, topic_api, caller_api)
Definition: master.py:439
test.master.MasterApiTestCase._testUnregisterPublisherInvalid
def _testUnregisterPublisherInvalid(self)
Definition: master.py:252
test.master._MasterTestCase.master_uri
master_uri
Definition: master.py:76
test.master.MasterApiTestCase._testUnregisterServiceInvalid
def _testUnregisterServiceInvalid(self)
Definition: master.py:221
test.master.MasterApiTestCase._testUnregisterServiceSuccess
def _testUnregisterServiceSuccess(self)
Definition: master.py:162
test.master.MasterApiTestCase._subTestRegisterServiceSuccess
def _subTestRegisterServiceSuccess(self)
common test subroutine of both register and unregister tests.
Definition: master.py:130
test.master._MasterTestCase.caller_id
caller_id
Definition: master.py:72


test_rosmaster
Author(s): Ken Conley, Dirk Thomas , Jacob Perron
autogenerated on Tue May 20 2025 03:00:35