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 ## set_node_name() must be called prior to the unit test so that the test harness knows its
53 ## ROS name.
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 ## reimplementation of caller ID spec separately from rospy
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  ## validates a URI as being http(s)
81  def _checkUri(self, uri):
82  import urlparse
83  parsed = urlparse.urlparse(uri)
84  self.assert_(parsed[0] in ['http', 'https'], 'protocol [%s] in [%s] invalid'%(parsed[0], uri))
85  self.assert_(parsed[1], 'host missing [%s]'%uri)
86  if not sys.version.startswith('2.4'): #check not available on py24
87  self.assert_(parsed.port, 'port missing/invalid [%s]'%uri)
88 
89 ## Expects a single test node to be running with name 'test_node' and subscribed to 'test_string'
91 
92  ## validate master.getMasterUri(caller_id)
93  def _testGetMasterUri(self):
94  # test with bad arity
95  self.apiError(self.master.getMasterUri())
96  # test success
97  uri = self.apiSuccess(self.master.getMasterUri(self.caller_id))
98  self._checkUri(uri)
99 
100  # make sure we agree on ports
101  import urlparse
102  parsed = urlparse.urlparse(uri)
103  parsed2 = urlparse.urlparse(self.master_uri)
104 
105  self.assertEquals(parsed.port, parsed2.port, "expected ports do not match")
106 
107  ## validate master.getPid(caller_id)
108  def _testGetPid(self):
109  # test with bad arity
110  self.apiError(self.master.getPid())
111  # test success
112  pid = self.apiSuccess(self.master.getPid(self.caller_id))
113  self.assert_(pid > 0)
114 
115  ## validate master.getUri(caller_id)
116  def _testGetUri(self):
117  # test with bad arity
118  self.apiError(self.master.getUri())
119  # test success
120  uri = self.apiSuccess(self.master.getUri(self.caller_id))
121  self.assert_(type(uri) == str)
122 
123  ## common test subroutine of both register and unregister tests. registers the common test cases
125  master = self.master
126 
127  caller_id = '/service_node'
128  caller_api = 'http://localhost:4567/'
129  service_base = '/service'
130 
131  # test success
132  for i in range(0, 10):
133  service_name = "%s-%s"%(service_base, i)
134  service_api = 'rosrpc://localhost:123%s/'%i
135  # register the service
136  self.apiSuccess(master.registerService(caller_id, service_name, service_api, caller_api))
137  # test master state
138  val = self.apiSuccess(master.lookupService(caller_id, service_name))
139  self.assertEquals(service_api, val)
140  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
141  self.assertEquals(caller_api, val)
142 
143  _, _, srvs = self.apiSuccess(master.getSystemState(self.caller_id))
144  for j in range(0, i+1):
145  jservice_name = "%s-%s"%(service_base, j)
146  jentry = [jservice_name, [caller_id]]
147  self.assert_(jentry in srvs, "master service list %s is missing %s"%(srvs, jentry))
148 
149  # TODO: have to test subscriber callback
150  # TODO: validate with getSystemState()
151 
152  ## validate master.registerService(caller_id, service, service_api, caller_api)
155 
158  master = self.master
159  caller_id = '/service_node'
160  caller_api = 'http://localhost:4567/'
161  service_base = '/service'
162 
163  for i in range(0, 10):
164  service_name = "%s-%s"%(service_base, i)
165  service_api = 'rosrpc://localhost:123%s/'%i
166 
167  # unregister the service
168  code, msg, val = master.unregisterService(caller_id, service_name, service_api)
169  self.assertEquals(code, 1, "code != 1, return message was [%s]"%msg)
170 
171  # test the master state
172  self.apiError(master.lookupService(self.caller_id, service_name), "master has a reference to unregistered service. message from master for unregister was [%s]"%msg)
173 
174  if i < 9:
175  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
176  self.assertEquals(caller_api, val, "master prematurely invalidated node entry for [%s] (lookupNode)"%caller_id)
177 
178  _, _, srvs = self.apiSuccess(master.getSystemState(self.caller_id))
179  for j in range(0, i+1):
180  jservice_name = "%s-%s"%(service_base, j)
181  jentry = [jservice_name, [caller_id]]
182  self.assert_(jentry not in srvs, "master service list %s should not have %s"%(srvs, jentry))
183  for j in range(i+1, 10):
184  jservice_name = "%s-%s"%(service_base, j)
185  jentry = [jservice_name, [caller_id]]
186  self.assert_(jentry in srvs, "master service list %s is missing %s"%(srvs, jentry))
187 
188  # TODO: have to test subscriber callback
189 
190  # Master's state should be zero'd out now
191 
192  # - #457 make sure that lookupNode isn't returning stale info
193  self.apiError(master.lookupNode(self.caller_id, caller_id), "master has a stale reference to unregistered service node API")
194  _, _, srvs = self.apiSuccess(master.getSystemState(self.caller_id))
195  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')]
196  self.assertEquals(0, len(srvs), "all services should have been unregistered: %s"%srvs)
197 
199  master = self.master
200 
201  service = '/service'
202  service_api = 'rosrpc://localhost:1234/'
203  caller_api = 'http://localhost:4567/'
204 
205  # test with bad arity
206  self.apiError(master.registerService())
207  self.apiError(master.registerService(self.caller_id, service))
208  self.apiError(master.registerService(self.caller_id, service, service_api))
209 
210  # test with bad args
211  self.apiError(master.registerService(self.caller_id, '', service_api, caller_api))
212  self.apiError(master.registerService(self.caller_id, service, '', caller_api))
213  self.apiError(master.registerService(self.caller_id, service, service_api, ''))
214 
216  master = self.master
217 
218  service = '/service'
219  service_api = 'rosrpc://localhost:1234/'
220 
221  # test with bad arity
222  self.apiError(master.unregisterService())
223  self.apiError(master.unregisterService(self.caller_id, service))
224 
225  # test with bad args
226  self.apiError(master.unregisterService(self.caller_id, '', service_api))
227  self.apiError(master.unregisterService(self.caller_id, service, ''))
228 
230  master = self.master
231 
232  topic = '/pub_topic'
233  topic_type = 'test_rosmaster/String'
234  caller_api = 'http://localhost:4567/'
235 
236  # test with bad arity
237  self.apiError(master.registerPublisher())
238  self.apiError(master.registerPublisher(self.caller_id, topic))
239  self.apiError(master.registerPublisher(self.caller_id, topic, topic_type))
240 
241  # test with bad args
242  self.apiError(master.registerPublisher(self.caller_id, '', topic_type, caller_api))
243  self.apiError(master.registerPublisher(self.caller_id, topic, '', caller_api))
244  self.apiError(master.registerPublisher(self.caller_id, topic, topic_type, ''))
245 
247  master = self.master
248 
249  topic = '/pub_topic'
250  caller_api = 'http://localhost:4567/'
251 
252  # test with bad arity
253  self.apiError(master.unregisterPublisher())
254  self.apiError(master.unregisterPublisher(self.caller_id, topic))
255 
256  # test with bad args
257  self.apiError(master.unregisterPublisher(self.caller_id, '', caller_api))
258  self.apiError(master.unregisterPublisher(self.caller_id, topic, ''))
259 
261  master = self.master
262 
263  topic = '/sub_topic'
264  topic_type = 'test_rosmaster/String'
265  caller_api = 'http://localhost:4567/'
266 
267  # test with bad arity
268  self.apiError(master.registerSubscriber())
269  self.apiError(master.registerSubscriber(self.caller_id, topic))
270  self.apiError(master.registerSubscriber(self.caller_id, topic, topic_type))
271 
272  # test with bad args
273  self.apiError(master.registerSubscriber(self.caller_id, '', topic_type, caller_api))
274  self.apiError(master.registerSubscriber(self.caller_id, topic, '', caller_api))
275  self.apiError(master.registerSubscriber(self.caller_id, topic, topic_type, ''))
276 
278  master = self.master
279 
280  topic = '/sub_topic'
281  caller_api = 'http://localhost:4567/'
282 
283  # test with bad arity
284  self.apiError(master.registerSubscriber())
285  self.apiError(master.registerSubscriber(self.caller_id, topic))
286 
287  # test with bad args
288  self.apiError(master.unregisterSubscriber(self.caller_id, '', caller_api))
289  self.apiError(master.unregisterSubscriber(self.caller_id, topic, ''))
290 
291  ## common test subroutine of both register and unregister tests. registers the common test cases
293  master = self.master
294 
295  caller_id = '/pub_node'
296  caller_api = 'http://localhost:4567/'
297  topic_base = '/pub_topic'
298  topic_type = 'test_rosmaster/String'
299 
300  # test success
301  for i in range(0, 10):
302  topic_name = "%s-%s"%(topic_base, i)
303  # register the topic
304  self.apiSuccess(master.registerPublisher(caller_id, topic_name, topic_type, caller_api))
305  # test master state
306  # - master knows caller_id
307  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
308  self.assertEquals(caller_api, val)
309  # - master knows topic type
310  val = self.apiSuccess(master.getPublishedTopics(self.caller_id, '/'))
311  self.assert_([topic_name, topic_type] in val, "master does not know topic type: %s"%val)
312  # - test new api as well
313  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
314  self.assert_([topic_name, topic_type] in val, "master does not know topic type: %s"%val)
315 
316  pubs, _, _ = self.apiSuccess(master.getSystemState(self.caller_id))
317  for j in range(0, i+1):
318  jtopic_name = "%s-%s"%(topic_base, j)
319  jentry = [jtopic_name, [caller_id]]
320  self.assert_(jentry in pubs, "master pub/sub list %s is missing %s"%(pubs, jentry))
321 
322  # TODO: have to test subscriber callback
323 
324  ## #591: this test may change if we make registering '*' unsupported
326  master = self.master
327  caller_id = '/pub_node'
328  caller_api = 'http://localhost:4567/'
329  topic_name = '/type_test_pub_topic'
330 
331  # register anytype first
332  val = self.apiSuccess(master.registerPublisher(caller_id, topic_name, '*', caller_api))
333  self.assertEquals([], val) # should report no subscribers
334  val = self.apiSuccess(master.getPublishedTopics(self.caller_id, '/'))
335  self.assert_([topic_name, '*'] in val, "master is not reporting * as type: %s"%val)
336  # - test new api as well
337  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
338  self.assert_([topic_name, '*'] in val, "master is not reporting * as type: %s"%val)
339 
340  # register a grounded type and make sure that '*' can't overwrite it
341  for t in ['test_rosmaster/String', '*']:
342  val = self.apiSuccess(master.registerPublisher(caller_id, topic_name, t, caller_api))
343  self.assertEquals([], val) # should report no subscribers
344  val = self.apiSuccess(master.getPublishedTopics(self.caller_id, '/'))
345  self.assert_([topic_name, 'test_rosmaster/String'] in val, "master is not reporting test_rosmaster/String as type: %s"%val)
346 
347  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
348  self.assert_([topic_name, 'test_rosmaster/String'] in val, "master is not reporting test_rosmaster/String as type: %s"%val)
349 
350  ## validate master.registerPublisher(caller_id, topic, topic_api, caller_api)
353 
354  # a couple more test cases to verify that registerPublisher's return value is correct
355  master = self.master
356  topic = '/pub_topic-0'
357  type = 'test_rosmaster/String'
358  pub_caller_api = 'http://localhost:4567/'
359 
360  subs = []
361  for i in range(5678, 5685):
362  api = 'http://localhost:%s'%i
363  subs.append(api)
364  self.apiSuccess(master.registerSubscriber('/sub_node-%i'%i, topic, type, api))
365  val = self.apiSuccess(master.registerPublisher('/pub_node', topic, type, pub_caller_api))
366  self.assertEquals(subs, val)
367 
370  master = self.master
371  caller_id = '/pub_node'
372  caller_api = 'http://localhost:4567/'
373  topic_base = '/pub_topic'
374 
375  for i in range(0, 10):
376  topic_name = "%s-%s"%(topic_base, i)
377 
378  # unregister the topic
379  code, msg, val = master.unregisterPublisher(caller_id, topic_name, caller_api)
380  self.assertEquals(code, 1, "code != 1, return message was [%s]"%msg)
381 
382  # test the master state
383  if i < 9:
384  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
385  self.assertEquals(caller_api, val, "master prematurely invalidated node entry for [%s] (lookupNode)"%caller_id)
386 
387  pubs, _, _ = self.apiSuccess(master.getSystemState(self.caller_id))
388  for j in range(0, i+1):
389  jtopic_name = "%s-%s"%(topic_base, j)
390  jentry = [jtopic_name, [caller_id]]
391  self.assert_(jentry not in pubs, "master pub/sub list %s should not have %s"%(pubs, jentry))
392  for j in range(i+1, 10):
393  jtopic_name = "%s-%s"%(topic_base, j)
394  jentry = [jtopic_name, [caller_id]]
395  self.assert_(jentry in pubs, "master pub/sub list %s is missing %s"%(pubs, jentry))
396 
397  # TODO: have to test subscriber callback
398 
399  # - #457 make sure that lookupNode isn't returning stale info
400  self.apiError(master.lookupNode(self.caller_id, caller_id), "master has a stale reference to unregistered topic node API. pubs are %s"%pubs)
401 
402  ## common test subroutine of both register and unregister tests. registers the common test cases
403  ## 'simple' test cases do not setup any publisher state to validate against
405  master = self.master
406 
407  caller_id = '/sub_node'
408  caller_api = 'http://localhost:4567/'
409  topic_base = '/sub_topic'
410  topic_type = 'test_rosmaster/String'
411 
412  # test success
413  for i in range(0, 10):
414  topic_name = "%s-%s"%(topic_base, i)
415  # register the topic
416  self.apiSuccess(master.registerSubscriber(caller_id, topic_name, topic_type, caller_api))
417  # test master state
418  # - master knows caller_id
419  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
420  self.assertEquals(caller_api, val)
421 
422  # - master should know topic type
423  val = self.apiSuccess(master.getTopicTypes(self.caller_id))
424  self.assert_([topic_name, topic_type] in val, "master does not know topic type: %s"%val)
425 
426  _, subs, _ = self.apiSuccess(master.getSystemState(self.caller_id))
427  for j in range(0, i+1):
428  jtopic_name = "%s-%s"%(topic_base, j)
429  jentry = [jtopic_name, [caller_id]]
430  self.assert_(jentry in subs, "master pub/sub list %s is missing %s"%(subs, jentry))
431 
432  ## validate master.registerSubscriber(caller_id, topic, topic_api, caller_api)
435 
438  master = self.master
439  caller_id = '/sub_node'
440  caller_api = 'http://localhost:4567/'
441  topic_base = '/sub_topic'
442 
443  for i in range(0, 10):
444  topic_name = "%s-%s"%(topic_base, i)
445 
446  # unregister the topic
447  code, msg, val = master.unregisterSubscriber(caller_id, topic_name, caller_api)
448  self.assertEquals(code, 1, "code != 1, return message was [%s]"%msg)
449 
450  # test the master state
451  if i < 9:
452  val = self.apiSuccess(master.lookupNode(self.caller_id, caller_id))
453  self.assertEquals(caller_api, val, "master prematurely invalidated node entry for [%s] (lookupNode)"%caller_id)
454 
455  _, subs, _ = self.apiSuccess(master.getSystemState(self.caller_id))
456  for j in range(0, i+1):
457  jtopic_name = "%s-%s"%(topic_base, j)
458  jentry = [jtopic_name, [caller_id]]
459  self.assert_(jentry not in subs, "master pub/sub list %s should not have %s"%(subs, jentry))
460  for j in range(i+1, 10):
461  jtopic_name = "%s-%s"%(topic_base, j)
462  jentry = [jtopic_name, [caller_id]]
463  self.assert_(jentry in subs, "master pub/sub list %s is missing %s"%(subs, jentry))
464 
465  # - #457 make sure that lookupNode isn't returning stale info
466  self.apiError(master.lookupNode(self.caller_id, caller_id), "master has a stale reference to unregistered topic node API. subs are %s"%subs)
467 
468 
def _testRegisterServiceSuccess(self)
validate master.registerService(caller_id, service, service_api, caller_api)
Definition: master.py:153
def _testRegisterServiceInvalid(self)
Definition: master.py:198
def __init__(self, args)
Definition: master.py:69
def _testRegisterPublisherInvalid(self)
Definition: master.py:229
def get_caller_id()
reimplementation of caller ID spec separately from rospy
Definition: master.py:61
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
def _testGetUri(self)
validate master.getUri(caller_id)
Definition: master.py:116
def _testUnregisterPublisherSuccess(self)
Definition: master.py:368
Expects a single test node to be running with name &#39;test_node&#39; and subscribed to &#39;test_string&#39;.
Definition: master.py:90
def _testRegisterPublisherSuccess(self)
validate master.registerPublisher(caller_id, topic, topic_api, caller_api)
Definition: master.py:351
def _subTestRegisterSubscriberSimpleSuccess(self)
common test subroutine of both register and unregister tests.
Definition: master.py:404
def _testUnregisterSubscriberInvalid(self)
Definition: master.py:277
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
def _testRegisterSubscriberInvalid(self)
Definition: master.py:260
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
def _testRegisterSubscriberSimpleSuccess(self)
validate master.registerSubscriber(caller_id, topic, topic_api, caller_api)
Definition: master.py:433
def _testGetPid(self)
validate master.getPid(caller_id)
Definition: master.py:108
def _testGetMasterUri(self)
validate master.getMasterUri(caller_id)
Definition: master.py:93
def _subTestRegisterPublisherSuccess(self)
common test subroutine of both register and unregister tests.
Definition: master.py:292
def _checkUri(self, uri)
validates a URI as being http(s)
Definition: master.py:81
def _testUnregisterServiceInvalid(self)
Definition: master.py:215
def _testUnregisterSubscriberSuccess(self)
Definition: master.py:436
def _subTestRegisterServiceSuccess(self)
common test subroutine of both register and unregister tests.
Definition: master.py:124
def _testUnregisterServiceSuccess(self)
Definition: master.py:156
def _testUnregisterPublisherInvalid(self)
Definition: master.py:246
def _testRegisterPublisherTypes(self)
#591: this test may change if we make registering &#39;*&#39; unsupported
Definition: master.py:325


test_rosmaster
Author(s): Ken Conley
autogenerated on Sun Feb 3 2019 03:30:20