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 testMaster: ROS integration test cases for master XML-RPC API
00036
00037 To run, invoke nodes/testMaster
00038 """
00039
00040 import os, sys, getopt, traceback, logging, socket
00041 import datetime, math, random
00042 try:
00043 from xmlrpc.client import DateTime, ServerProxy
00044 except ImportError:
00045 from xmlrpclib import DateTime, ServerProxy
00046 import unittest
00047 import rospy
00048 from rostest import *
00049 from testSlave import msMain
00050
00051 MYPKG = 'test_rosmaster'
00052
00053 HAS_PARAM = True
00054
00055 singletest = 'testGetFlowNames'
00056 singletest = None
00057
00058
00059 def verifyNodeAddress(master, callerId, name, machine, addr, port):
00060 if not name:
00061 raise Exception("name is None")
00062 rmachine, raddr, rport = apiSuccess(master.getNodeAddress(callerId, name))
00063 if machine:
00064 assert rmachine == machine, "Node [%s] is running on '%s' instead of '%s'"%(name, rmachine, machine)
00065 if port:
00066 assert rport == port, "Node [%s] is running on '%s' instead of '%s'"%(name, rport, port)
00067 else:
00068 assert rport, "Node [%s] does not have a registered port"%name
00069 if addr:
00070 if addr == 'localhost':
00071 addr = socket.gethostname()
00072 if raddr == 'localhost':
00073 raddr = socket.gethostname()
00074 addrinfo = socket.getaddrinfo(addr, 0, 0, 0, socket.SOL_TCP)
00075 raddrinfo = socket.getaddrinfo(raddr, 0, 0, 0, socket.SOL_TCP)
00076 assert raddrinfo == addrinfo, "%s!=%s" % (raddrinfo, addrinfo)
00077
00078 apiSuccess(ServerProxy("http://%s:%s/"%(raddr, rport)).getPid(''))
00079
00080 def testGraphState(master, graphNodes, graphFlows):
00081 graph = apiSuccess(master.getGraph(''))
00082 diff = set(graph[0]) ^ set(graphNodes)
00083 assert not diff, "Graph nodes %s does not match expected %s: %s"%(graph[0], graphNodes, diff)
00084
00085 expectedFlows = ["%s:%s:1"%f for f in graphFlows]
00086 print graph[1]
00087 remoteFlows = ["%s:%s:%s"%(src,snk,c) for (src,snk,c) in graph[1]]
00088 if expectedFlows or remoteFlows:
00089
00090 diff = set(expectedFlows) ^ set(remoteFlows)
00091 assert not diff, "Graph flows %s does not match expected %s: %s"%(expectedFlows, remoteFlows, diff)
00092
00093 def testParamState(master, myState):
00094 callerId = 'master'
00095 for (k, v) in myState.items():
00096 if HAS_PARAM:
00097 assert apiSuccess(master.hasParam(callerId, k))
00098 print "verifying parameter %s"%k
00099 v2 = apiSuccess(master.getParam(callerId, k))
00100 if isinstance(v2, DateTime):
00101 assert DateTime(v) == v2, "[%s]: %s != %s, %s"%(k, v, v2, v2.__class__)
00102 else:
00103 assert v == v2, "[%s]: %s != %s, %s"%(k, v, v2, v2.__class__)
00104 paramNames = myState.keys()
00105 remoteParamNames = apiSuccess(master.getParamNames(callerId))
00106 assert not set(paramNames) ^ set(remoteParamNames), "parameter server keys do not match local"
00107
00108 class ParamServerTestCase(ROSGraphTestCase):
00109 """Parameter Server API Test Cases"""
00110
00111 def setUp(self):
00112 super(ParamServerTestCase, self).setUp()
00113
00114 def tearDown(self):
00115 super(ParamServerTestCase, self).tearDown()
00116
00117 def _testSetParam(self, ctx, myState, testVals, master):
00118 for type, vals in testVals:
00119 try:
00120 if ctx:
00121 callerId = "%s.node"%ctx
00122 else:
00123 callerId = "node"
00124 count = 0
00125 for val in vals:
00126 key = "%s-%s"%(type,count)
00127 print "master.setParam(%s,%s,%s)"%(callerId, key, val)
00128 master.setParam(callerId, key, val)
00129 if HAS_PARAM:
00130 assert apiSuccess(master.hasParam(callerId, key))
00131 if ctx:
00132 trueKey = "%s.%s"%(ctx, key)
00133 else:
00134 trueKey = key
00135 myState[trueKey] = val
00136 count += 1
00137 except:
00138 assert "getParam failed on type[%s], val[%s]"%(type,val)
00139 testParamState(master, myState)
00140
00141 def testParamValues(self):
00142 """testParamValues: test storage of all XML-RPC compatible types"""
00143 try:
00144 from xmlrpc.client import Binary
00145 except ImportError:
00146 from xmlrpclib import Binary
00147 testVals = [
00148 ['int', [0, 1024, 2147483647, -2147483647]],
00149 ['boolean', [True, False]],
00150 ['string', ['', '\0', 'x', 'hello', ''.join([chr(n) for n in range(0, 255)])]],
00151 ['double', [0.0, math.pi, -math.pi, 3.4028235e+38, -3.4028235e+38]],
00152
00153 ['datetime', [datetime.datetime(2005, 12, 6, 12, 13, 14), datetime.datetime(1492, 12, 6, 12, 13, 14)]],
00154 ['base64', [Binary(''), Binary('\0'), Binary(''.join([chr(n) for n in range(0, 255)]))]],
00155 ['struct', [{ "a": 2, "b": 4},
00156 {"a" : "b", "c" : "d"},
00157 {"a" : {"b" : { "c" : "d"}}}]],
00158 ['array', [[], [1, 2, 3], ['a', 'b', 'c'], [0.0, 0.1, 0.2, 2.0, 2.1, -4.0],
00159 [1, 'a', math.pi], [[1, 2, 3], ['a', 'b', 'c'], [1.0, 2.1, 3.2]]]
00160 ],
00161 ]
00162 master = self.master
00163
00164 print "Putting parameters onto the server"
00165
00166 contexts = ['', 'scope1', 'scope2', 'scope.subscope1', 'scope.sub1.sub2']
00167 myState = {}
00168 for ctx in contexts:
00169 self._testSetParam(ctx, myState, testVals, master)
00170
00171 print "Deleting all of our parameters"
00172
00173 paramKeys = myState.keys()
00174 for key in paramKeys:
00175 apiSuccess(master.deleteParam('', key))
00176 del myState[key]
00177 testParamState(master, myState)
00178
00179 def testEncapsulation(self):
00180 """testEncapsulation: test encapsulation: setting same parameter at different levels"""
00181 master = self.master
00182 myState = {}
00183 testParamState(master, myState)
00184
00185 testContexts = ['', 'en', 'en.sub1', 'en.sub2', 'en.sub1.sub2']
00186 for c in testContexts:
00187 testKey = 'param1'
00188 testVal = random.randint(-1000000, 100000)
00189 if c:
00190 callerId = "%s.node"%c
00191 trueKey = "%s.%s"%(c,testKey)
00192 else:
00193 callerId ="node"
00194 trueKey = testKey
00195 master.setParam(callerId, testKey, testVal)
00196 myState[trueKey] = testVal
00197
00198 v1 = apiSuccess(master.getParam('', trueKey))
00199 v2 = apiSuccess(master.getParam(callerId, testKey))
00200 assert v1 == v2, "[%s]: %s vs. [%s,%s]: %s"%(trueKey, v1, callerId, testKey, v2)
00201 if HAS_PARAM:
00202 assert apiSuccess(master.hasParam(callerId, testKey)), testKey
00203 assert apiSuccess(master.hasParam('node', trueKey)), trueKey
00204
00205 testParamState(master, myState)
00206
00207 def testDotLocalNames(self):
00208 master = self.master
00209 myState = {}
00210 testParamState(master, myState)
00211
00212 testContexts = ['', 'sub1', 'sub1.sub2', 'sub1.sub2.sub3']
00213 for c in testContexts:
00214 if c:
00215 callerId = "%s.node"%c
00216 else:
00217 callerId = "node"
00218 testKey = ".param1"
00219 testVal = random.randint(-1000000, 100000)
00220 master.setParam(callerId, testKey, testVal)
00221 trueKey = callerId+testKey
00222 myState[trueKey] = testVal
00223
00224 v1 = apiSuccess(master.getParam('node', trueKey))
00225 v2 = apiSuccess(master.getParam(callerId, testKey))
00226 assert v1 == v2, "[%s]: %s vs. [%s,%s]: %s"%(trueKey, v1, callerId, testKey, v2)
00227 if HAS_PARAM:
00228 assert apiSuccess(master.hasParam(callerId, testKey)), testKey
00229 assert apiSuccess(master.hasParam('node', trueKey)), trueKey
00230
00231
00232 testKey = "altnode.param2"
00233 testVal = random.randint(-1000000, 100000)
00234 master.setParam(callerId, testKey, testVal)
00235 if c:
00236 trueKey = "%s.%s"%(c,testKey)
00237 altCallerId = "%s.altnode"%c
00238 else:
00239 trueKey = testKey
00240 altCallerId = "altnode"
00241 myState[trueKey] = testVal
00242
00243 v1 = apiSuccess(master.getParam(altCallerId, ".param2"))
00244 v2 = apiSuccess(master.getParam(callerId, testKey))
00245 assert v1 == v2
00246 if HAS_PARAM:
00247 assert apiSuccess(master.hasParam(callerId, testKey)), testKey
00248 assert apiSuccess(master.hasParam(altCallerId, ".param2"))
00249
00250 testParamState(master, myState)
00251
00252 def testScopeUp(self):
00253 """testScopeUp: test that parameter server can chain up scopes to find/delete parameters"""
00254 master = self.master
00255 myState = {}
00256 testParamState(master, myState)
00257
00258 testVal = random.randint(-1000000, 100000)
00259 master.setParam('', 'uparam1', testVal)
00260 myState['uparam1'] = testVal
00261 assert testVal == apiSuccess(master.getParam('node', 'uparam1'))
00262 assert testVal == apiSuccess(master.getParam('uptest.node', 'uparam1'))
00263 assert testVal == apiSuccess(master.getParam('uptest.sub1.node', 'uparam1'))
00264 assert testVal == apiSuccess(master.getParam('uptest.sub1.sub2.node', 'uparam1'))
00265
00266 testVal = random.randint(-1000000, 100000)
00267 master.setParam('uptest2.sub1.node', 'uparam2', testVal)
00268 myState['uptest2.sub1.uparam2'] = testVal
00269 assert testVal == apiSuccess(master.getParam('uptest2.sub1.node', 'uparam2'))
00270 assert testVal == apiSuccess(master.getParam('uptest2.sub1.sub2.node', 'uparam2'))
00271 assert testVal == apiSuccess(master.getParam('uptest2.sub1.sub2.sub3.node', 'uparam2'))
00272 testParamState(master, myState)
00273
00274
00275 apiSuccess(master.deleteParam('uptest.sub1.sub2.node', 'uparam1'))
00276 del myState['uparam1']
00277 testParamState(master, myState)
00278 apiSuccess(master.deleteParam('uptest2.sub1.sub2.sub3.node', 'uparam2'))
00279 del myState['uptest2.sub1.uparam2']
00280 testParamState(master, myState)
00281
00282 def testScopeDown(self):
00283 """testScopeDown: test scoping rules for sub contexts"""
00284 master = self.master
00285 myState = {}
00286 testParamState(master, myState)
00287
00288
00289 testVal = random.randint(-1000000, 100000)
00290 master.setParam('down.one.two.three.node', 'dparam1', testVal)
00291 myState['down.one.two.three.dparam1'] = testVal
00292 if HAS_PARAM:
00293 assert not apiSuccess(master.hasParam('down.one', 'dparam1'))
00294 assert not apiSuccess(master.hasParam('down.one.two', 'dparam1'))
00295 apiError(master.getParam('down.one.node', 'dparam1'))
00296 apiError(master.getParam('down.one.two.node', 'dparam1'))
00297
00298
00299 testVal = random.randint(-1000000, 100000)
00300 master.setParam('node', 'down2.dparam2', testVal)
00301 myState['down2.dparam2'] = testVal
00302 assert testVal == apiSuccess(master.getParam('down2.node', 'dparam2'))
00303 assert testVal == apiSuccess(master.getParam('', 'down2.dparam2'))
00304 if HAS_PARAM:
00305 assert not apiSuccess(master.hasParam('down2.node', 'down2.dparam2'))
00306 apiError(master.getParam('down2.node', 'down2.dparam2'))
00307 testParamState(master, myState)
00308
00309
00310 testVal = random.randint(-1000000, 100000)
00311 master.setParam('node', 'down3.sub.dparam3', testVal)
00312 myState['down3.sub.dparam3'] = testVal
00313 assert testVal == apiSuccess(master.getParam('down3.sub.node', 'dparam3'))
00314 assert testVal == apiSuccess(master.getParam('down3.node', 'sub.dparam3'))
00315 assert testVal == apiSuccess(master.getParam('', 'down3.sub.dparam3'))
00316 assert testVal == apiSuccess(master.getParam('down3.sub.sub2.node', 'dparam3'))
00317 if HAS_PARAM:
00318 assert not apiSuccess(master.hasParam('down3.sub.node', 'sub.dparam3'))
00319 assert not apiSuccess(master.hasParam('down3.sub.node', 'down3.sub.dparam3'))
00320 apiError(master.getParam('down3.sub.node', 'sub.dparam3'))
00321 apiError(master.getParam('down3.sub.node', 'down3.sub.dparam3'))
00322 testParamState(master, myState)
00323
00324
00325 master.setParam('node', 'down4.sub.dparam4A', testVal)
00326 apiSuccess(master.deleteParam('down4.sub.node', 'dparam4A'))
00327 if HAS_PARAM:
00328 assert not apiSuccess(master.hasParam('down4.sub', 'dparam4A'))
00329 master.setParam('node', 'down4.sub.dparam4B', testVal)
00330 apiSuccess(master.deleteParam('down4.node', 'sub.dparam4B'))
00331 if HAS_PARAM:
00332 assert not apiSuccess(master.hasParam('down4.sub', 'dparam4B'))
00333 master.setParam('node', 'down4.sub.dparam4C', testVal)
00334 apiSuccess(master.deleteParam('', 'down4.sub.dparam4C'))
00335 if HAS_PARAM:
00336 assert not apiSuccess(master.hasParam('down4.sub.node', 'dparam4C'))
00337 testParamState(master, myState)
00338
00339 class MasterTestCase(ROSGraphTestCase):
00340 """Master API Test Cases -- those not covered by ParamServer and AddKillNode"""
00341
00342 def setUp(self):
00343 super(MasterTestCase, self).setUp()
00344
00345 def tearDown(self):
00346 super(MasterTestCase, self).tearDown()
00347
00348 def _verifyFlowNameState(self, master, state):
00349 flows = apiSuccess(master.getFlowNames('node1', ''))
00350 assert len(flows) == len(state.values()), "Master reported a different number of flows"
00351 for val in state.values():
00352 assert val in flows, "flows does not contain %s : %s"%(val, flows)
00353
00354 def testPromoteFlow(self):
00355 master = self.master
00356 state = {}
00357 callerId = 'node1'
00358 type = 'common_flows/String'
00359
00360 apiSuccess(master.registerNode(callerId, 'node1', 'localhost', 1234, []))
00361 for i in range(1, 4):
00362 for dir in ['inflow', 'outflow']:
00363 locator = 'node1:%s%s'%(dir, i)
00364 apiSuccess(master.registerFlow(callerId, 'node1', locator, dir, type))
00365 state[locator] = [locator, dir, type, 0]
00366
00367
00368 apiError(master.promoteFlow(callerId, 'node1:notAFlow', 'node1:newNotAFlow'))
00369
00370 apiError(master.promoteFlow(callerId, ':outflow1', 'node1:newNotAFlow'))
00371
00372
00373
00374 dir = 'outflow'
00375 apiSuccess(master.promoteFlow(callerId, 'node1:outflow1', ':outflow1'))
00376 state[':outflow1'] = [':outflow1', dir, type, 1]
00377
00378 apiSuccess(master.promoteFlow(callerId, '.:outflow2', ':outflow2'))
00379 state[':outflow2'] = [':outflow2', dir, type, 1]
00380
00381
00382
00383 dir = 'inflow'
00384 tests = [
00385 ['node1:inflow1', 'node1:newInflow1'],
00386 ['node1:inflow2', 'sibling:inflow2'],
00387 ['node1:inflow3', 'node1:subgraph1:inflow3']
00388 ]
00389 for source, target in tests:
00390 apiSuccess(master.promoteFlow(callerId, source, target))
00391 state[target] = [target, dir, type, 1]
00392
00393 self._verifyFlowNameState(master, state)
00394
00395
00396 apiError(master.promoteFlow(callerId, 'node1:outflow1', 'node1:outflow2'))
00397 apiError(master.promoteFlow(callerId, 'node1:outflow2', ':outflow1'))
00398 apiError(master.promoteFlow(callerId, 'node1:inflow1', 'sibling:inflow2'))
00399
00400
00401
00402
00403
00404 def testRegisterFlow(self):
00405 master = self.master
00406 state = {}
00407 type = 'common_flows/String'
00408 for callerId in ['node1', 'subgraph.node1', 'grandparent.parent.node1']:
00409
00410 apiSuccess(master.registerNode(callerId, 'node1', 'localhost', 1234, []))
00411 for i in range(1, 4):
00412 for dir in ['inflow', 'outflow']:
00413 if dir == 'inflow':
00414 locator = 'node1:%s%s'%(dir, i)
00415 else:
00416 locator = '.:%s%s'%(dir, i)
00417 apiSuccess(master.registerFlow(callerId, 'node1', locator, dir, type))
00418 realLocator = '%s:%s%s'%(callerId, dir, i)
00419 state[realLocator] = [realLocator, dir, type, 0]
00420
00421 apiError(master.registerFlow(callerId, 'notNode', 'notANode:outflow', 'outflow', type))
00422
00423 apiError(master.registerFlow(callerId, 'node1', '', 'outflow', type))
00424 apiError(master.registerFlow(callerId, 'node1', 'badflow1', 'outflow', type))
00425
00426 apiError(master.registerFlow(callerId, 'node1', 'node1:badflow2', 'spiralflow', type))
00427
00428 apiError(master.registerFlow(callerId, 'node1', 'node1:badflow3', 'outflow', ''))
00429 apiError(master.registerFlow(callerId, 'node1', 'node1:badflow4', 'outflow', 'faketype'))
00430
00431
00432 apiError(master.registerFlow(callerId, 'node1', 'node1:outflow1', 'outflow', type))
00433 apiSuccess(master.promoteFlow(callerId, 'node1:outflow1', 'node1:newOutflow1'))
00434 state['%s:newOutflow1'%callerId] = ['node1:newOutflow1', dir, type, 1]
00435 apiError(master.registerFlow(callerId, 'node1', 'node1:newOutflow1', 'outflow', type))
00436
00437 self._verifyFlowNameState(master, state)
00438
00439 def testUnregisterFlow(self):
00440 master = self.master
00441 state = {}
00442 type = 'common_flows/String'
00443 for callerId in ['node1', 'subgraph.node1', 'grandparent.parent.node1']:
00444
00445 apiSuccess(master.registerNode(callerId, 'node1', 'localhost', 1234, []))
00446 for i in range(1, 4):
00447 for dir in ['inflow', 'outflow']:
00448 if dir == 'inflow':
00449 locator = rlocator = 'node1:%s%s'%(dir, i)
00450 else:
00451 locator = '.:%s%s'%(dir, i)
00452 rlocator = 'node1:%s%s'%(dir, i)
00453 apiSuccess(master.registerFlow(callerId, 'node1', locator, dir, type))
00454 realLocator = '%s:%s%s'%(callerId, dir, i)
00455 state[realLocator] = [realLocator, dir, type, 0]
00456
00457 self._verifyFlowNameState(master, state)
00458
00459
00460 apiError(master.unregisterFlow(callerId, 'notANode:outflow'))
00461 apiError(master.unregisterFlow(callerId, ''))
00462 apiError(master.unregisterFlow(callerId.replace('node1', 'node2'), 'outflow1'))
00463
00464 apiSuccess(master.unregisterFlow(callerId, 'node1:outflow1'))
00465 del state['%s:outflow1'%callerId]
00466 apiSuccess(master.unregisterFlow(callerId, '.:outflow2'))
00467 del state['%s:outflow2'%callerId]
00468 apiSuccess(master.unregisterFlow(callerId.replace('node1', 'node2'), 'node1:outflow3'))
00469 del state['%s:outflow3'%callerId]
00470 apiSuccess(master.unregisterFlow('master', '%s:inflow1'%callerId))
00471 del state['%s:inflow1'%callerId]
00472
00473 self._verifyFlowNameState(master, state)
00474
00475
00476 apiError(master.unregisterFlow(callerId, 'node1:outflow1'))
00477
00478
00479 apiSuccess(master.promoteFlow(callerId, 'node1:inflow3', ':inflow3A'))
00480 apiSuccess(master.promoteFlow(callerId, ':inflow3A', ':inflow3B'))
00481
00482 apiSuccess(master.unregisterFlow(callerId, 'node1:inflow3'))
00483 del state['%s:inflow3'%callerId]
00484
00485 self._verifyFlowNameState(master, state)
00486
00487 def testGetFlowNames(self):
00488 master = self.master
00489 pkg,node = testNode
00490 subgraph = 'sub1.sub2'
00491 name = 'testGFN_A'
00492 port = apiSuccess(master.addNode('caller', subgraph, name, pkg, node, TEST_MACHINE, 0))
00493
00494
00495 testFlowNames = ["%s:%s"%(name, v) for v in ["in", "out"]]
00496 print "FLOW NAMES", apiSuccess(master.getFlowNames('master', ''))
00497 flows = apiSuccess(master.getFlowNames('%s.caller'%subgraph, ''))
00498 assert not set([x[0] for x in flows]) ^ set(testFlowNames), "%s vs. %s"%([x[0] for x in flows], testFlowNames)
00499
00500 inDirs = [x[1] for x in flows if x[0].endswith(':in')]
00501 outDirs = [x[1] for x in flows if x[0].endswith(':out')]
00502 assert not filter(lambda x: x != "inflow", inDirs), inDirs
00503 assert not filter(lambda x: x != "outflow", outDirs), outDirs
00504 assert not filter(lambda x: x != "common_flows/String", [x[2] for x in flows])
00505 assert not filter(lambda x: x, [x[3] for x in flows])
00506
00507
00508 testFlowNames = ["%s.%s:%s"%(subgraph, name, v) for v in ["in", "out"]]
00509 flows = apiSuccess(master.getFlowNames('caller', subgraph))
00510 assert not set([x[0] for x in flows]) ^ set(testFlowNames), "%s vs. %s"%([x[0] for x in flows], testFlowNames)
00511 flows = apiSuccess(master.getFlowNames('caller', "%s.%s"%(subgraph, name)))
00512 assert not set([x[0] for x in flows]) ^ set(testFlowNames), "%s vs. %s"%([x[0] for x in flows], testFlowNames)
00513
00514 testFlowNames = ["sub2.%s:%s"%(name, v) for v in ["in", "out"]]
00515 flows = apiSuccess(master.getFlowNames('sub1.caller', 'sub2'))
00516 assert not set([x[0] for x in flows]) ^ set(testFlowNames), "%s vs. %s"%([x[0] for x in flows], testFlowNames)
00517
00518
00519 testFlowNames = ["%s.%s:%s"%(subgraph, name, v) for v in ["in", "out"]]
00520 flows = apiSuccess(master.getFlowNames('caller', ''))
00521 flowNames = [x[0] for x in flows]
00522 assert not set(flowNames) ^ set(testFlowNames)
00523
00524
00525 def testGetNodeAddress(self):
00526 def validate(val, callerId, name, port):
00527 assert len(val) == 3, "getNodeAddress did not return 3-element list for value field"
00528 assert type(val[0]) == str and type(val[1]) == str and type(val[2]) == int,\
00529 "getNodeAddress did not return (str, str, int) for value field"
00530 verifyNodeAddress(master, callerId, name, TEST_MACHINE, 'localhost', port)
00531
00532
00533
00534
00535
00536 master = self.master
00537
00538 code, msg, val = master.getNodeAddress('', 'testGetNodeAddress-fake')
00539 assert code == -1, "getNodeAddress did not return failure code 0 for non-existent node"
00540 assert len(val) == 3, "getNodeAddress did not return 3-element list for value field in error case"
00541 assert type(val[0]) == str and type(val[1]) == str and type(val[2]) == int,\
00542 "getNodeAddress did not return (str, str, int) for value field in error case"
00543
00544
00545 name = 'testGetNodeAddress-1'
00546 port = 7981
00547 pkg, node = testNode
00548 apiSuccess(master.addNode('', '', name, pkg, node, TEST_MACHINE, port))
00549 val = apiSuccess(master.getNodeAddress('', name))
00550 validate(val, '', name, port)
00551
00552
00553 name = 'testGetNodeAddress-2'
00554 port = 7982
00555 apiSuccess(master.addNode('', 'gna1.gna2', name, pkg, node, TEST_MACHINE, port))
00556
00557 tests = [
00558
00559 ['gna1.gna2.node', name],
00560 ['gna1.node', 'gna2.%s'%name],
00561 ['', 'gna1.gna2.%s'%name],
00562
00563 ['gna1.gna2.gna3.node', name],
00564 ]
00565 for test in tests:
00566 callerId, name = test
00567 validate(apiSuccess(master.getNodeAddress(callerId, name)), callerId, name, port)
00568
00569
00570 val = apiError(master.getNodeAddress('gna1.gna2', 'gna3.%s'%name))
00571
00572 def _verifyNodeDead(self, port):
00573 testUri = "http://localhost:%s/"%port
00574 try:
00575 ServerProxy(testUri).getPid('node')
00576 self.fail("test node is still running")
00577 except:
00578 pass
00579
00580 def testAddKillNode(self):
00581 """testAddKillNode: test adding then killing nodes"""
00582
00583 master = self.master
00584 pkg,node = testNode
00585 apiError(master.killNode('node','nonexistentNode'))
00586 name = 'testAddKillA'
00587 port = apiSuccess(master.addNode('node', 'subgraph', name, pkg, node, TEST_MACHINE, 0))
00588
00589 apiError(master.killNode('different.subgraph.node', name))
00590
00591 apiError(master.killNode('node', name))
00592
00593 apiError(master.killNode('subgraph.sub2.node', name))
00594
00595 apiSuccess(master.killNode('subgraph.node', name))
00596
00597
00598 tests = [['node', '', 'testAddKillB'],
00599 ['node', 'g1.g2', 'testAddKillB'],
00600 ['node', 'g1', 'testAddKillB'],
00601 ['g1.g2.node', 'g3', 'testAddKillB'],
00602 ]
00603 for callerId, subcontext, nodeName in tests:
00604 port = apiSuccess(master.addNode(callerId, subcontext, nodeName, pkg, node, TEST_MACHINE, 0))
00605 if subcontext:
00606 name = "%s.%s"%(subcontext, nodeName)
00607 else:
00608 name = nodeName
00609 apiSuccess(master.killNode(callerId, name))
00610 self._verifyNodeDead(port)
00611
00612 def testAddNode(self):
00613 """testAddNode: test master.addNode(callerId, subcontext, name, pkg, pkgNode, machine, port)"""
00614 master = self.master
00615 graphNodes = ['master']
00616 graphFlows = []
00617
00618 pkg, node = testNode
00619 errors = [
00620
00621 ['', 12, 'testAddNodeError1', pkg, node, TEST_MACHINE, 0],
00622
00623 ['', '', 123, pkg, node, TEST_MACHINE, 0],
00624
00625 ['', '', 'testAddNodeError2', 123, node, TEST_MACHINE, 0],
00626
00627 ['', '', 'testAddNodeError3', pkg, '', TEST_MACHINE, 0],
00628 ['', '', 'testAddNodeError4', pkg, 123, TEST_MACHINE, 0],
00629
00630 ['', '', 'testAddNodeError6', pkg, node, 'unknown', 0],
00631 ['', '', 'testAddNodeError7', pkg, 'noNode', 123, 0],
00632
00633 ['', '', 'testAddNodeError8', pkg, node, TEST_MACHINE, -80],
00634 ['', '', 'testAddNodeError9', pkg, node, TEST_MACHINE, "80"],
00635 ]
00636 for args in errors:
00637 try:
00638 apiError(master.addNode(*args))
00639 except Exception, e:
00640 self.fail("addNodeError case failed with args[%s] and exception [%s]"%(args, e))
00641
00642 apiFail(master.addNode('', '', 'testAddNodeFail1', pkg, 'notANode', TEST_MACHINE, 0))
00643
00644 testGraphState(master, graphNodes, graphFlows)
00645 tests = [[['','testAddNode1'], [TEST_MACHINE, 7980]],
00646 [['','testAddNode2'], [TEST_MACHINE, 0]],
00647 [['','testAddNode3'], ['', 0]],
00648 [['','testAddNode4'], [TEST_MACHINE, 0]],
00649 [['','testAddNode5'], [TEST_MACHINE, 0]],
00650 [['','testAddNode6'], [TEST_MACHINE, 0]],
00651 [['','testAddNode7'], [TEST_MACHINE, 0]],
00652
00653 [['push', 'testAddNode8'], [TEST_MACHINE, 0]],
00654 [['push.one.two', 'testAddNode9'], [TEST_MACHINE, 0]],
00655 [['stanford.addNodeTest','testAddNodeA'], [TEST_MACHINE, 0]],
00656 [['wg.addNodeTest', 'testAddNodeA'], [TEST_MACHINE, 0]],
00657 ]
00658 for fullname, args in tests:
00659 print "testAddNode: testing", fullname
00660 subcontext, name = fullname
00661 if subcontext:
00662 fullname = '%s.%s'%(subcontext, name)
00663 else:
00664 fullname = name
00665 machine, port = args
00666 apiSuccess(master.addNode('', subcontext, name, pkg, node, machine, port))
00667 verifyNodeAddress(master, '', fullname, machine, 'localhost', port)
00668 graphNodes.append(fullname)
00669 testGraphState(master, graphNodes, graphFlows)
00670
00671 apiSuccess(master.addNode('', subcontext, name, pkg, node, machine, port))
00672
00673
00674
00675
00676 port = apiSuccess(master.addNode('node', 'duplicate.test', 'nodeA', pkg, node, TEST_MACHINE, 0))
00677 apiError(master.addNode('node', 'duplicate.test', 'nodeA', pkg, node, TEST_MACHINE, port + 1))
00678 apiError(master.addNode('node', 'duplicate.test', 'nodeA', pkg+'foo', node, TEST_MACHINE, port))
00679 apiError(master.addNode('node', 'duplicate.test', 'nodeA', pkg, node+'foo', TEST_MACHINE, port))
00680
00681
00682 def testGetGraph(self):
00683
00684
00685 pass
00686
00687 def testAddMachine(self):
00688 master = self.master
00689 host, port = masterAddr
00690
00691
00692 apiError(master.addMachine('node', '', self.rosRoot, host, 22, '', ''))
00693 apiError(master.addMachine('node', 123, self.rosRoot, host, 22, '', ''))
00694
00695 apiError(master.addMachine('node', 'name', '', host, 22, '', ''))
00696 apiError(master.addMachine('node', 'name', 123, host, 22, '', ''))
00697
00698 apiError(master.addMachine('node', 'name', '', '', 22, '', ''))
00699 apiError(master.addMachine('node', 'name', '', 123, 22, '', ''))
00700
00701 apiError(master.addMachine('node', 'name', '', host, -22, '', ''))
00702 apiError(master.addMachine('node', 'name', '', host, "22", '', ''))
00703
00704 tests = [
00705 ['node', 'testAddMachine-1'],
00706 ['g1.node', 'testAddMachine-2'],
00707 ['g1.g2.g3.node', 'testAddMachine-3'],
00708 ['g1.g2.node', 'testAddMachine-4'],
00709 ]
00710 rosRoot = self.rosRoot
00711 for callerId, m in tests:
00712 apiSuccess(master.addMachine(callerId, m, rosRoot, host, 22, '', ''))
00713
00714 apiSuccess(master.addMachine(callerId, m, rosRoot, host, 22, '', ''))
00715
00716 apiError(master.addMachine(callerId, m, rosRoot+'/foo/', host, 22, '', ''))
00717 apiError(master.addMachine(callerId, m, rosRoot, 'www.google.com', 22, '', ''))
00718 apiError(master.addMachine(callerId, m, rosRoot, host, 21, '', ''))
00719 apiError(master.addMachine(callerId, m, rosRoot, host, 22, 'fake-user', ''))
00720 apiError(master.addMachine(callerId, m, rosRoot, host, 22, '', 'fake-password'))
00721
00722
00723
00724 def testRegisterNode_Flows(self):
00725
00726 pass
00727
00728 def testRegisterNode(self):
00729 master = self.master
00730 flows = []
00731
00732 apiError(master.registerNode('', '', 'localhost', 80, flows))
00733
00734 apiError(master.registerNode('', 'registerNodeFail2', '', 80, flows))
00735
00736 apiError(master.registerNode('', 'registerNodeFail3', 'localhost', -80, flows))
00737 apiError(master.registerNode('', 'registerNodeFail4', 'localhost', 0, flows))
00738
00739
00740
00741
00742
00743 testCases = [
00744 ['', 'registerNodeExternal-1'],
00745 ['', 'rne.registerNodeExternal-2'],
00746 ['rne', 'registerNodeExternal-3'],
00747 ['', 'rne.rne2.rne3.registerNodeExternal-4'],
00748 ['rne', 'rne2.rne3.registerNodeExternal-5'],
00749 ['rne.rne2.rne3', 'registerNodeExternal-6'],
00750 ]
00751 for context, name in testCases:
00752 try:
00753 if context:
00754 fullName = "%s.%s"%(context, name)
00755 callerId = "%s.node"%context
00756 else:
00757 fullName = name
00758 callerId = "node"
00759 startTestNode(fullName)
00760
00761
00762 timeoutT = time.time() + 4.0
00763 node = getTestNode()
00764 val = None
00765 while time.time() < timeoutT and not val:
00766 try:
00767 _, _, val = node.getPid('')
00768 except:
00769 pass
00770 assert val, "unable to start test node for registerNode test case"
00771
00772 verifyNodeAddress(master, callerId, name, None, testNodeAddr[0], testNodeAddr[1])
00773 finally:
00774 stopTestNode()
00775
00776 def testConnectFlow(self):
00777 master = self.master
00778 pkg, node = testNode
00779 graphNodes = ['master']
00780 graphFlows = []
00781 machine = TEST_MACHINE
00782 for i in range(1, 5):
00783 apiSuccess(master.addNode('m', '', 'baseTcfNode-%s'%i, pkg, node, machine, 0))
00784 graphNodes.append('baseTcfNode-%s'%i)
00785 apiSuccess(master.addNode('m', '', 'tcfNode-%s'%i, pkg, node, machine, 0))
00786 graphNodes.append('tcfNode-%s'%i)
00787 apiSuccess(master.addNode('m', 'tcf1', 'tcfNode-%s'%i, pkg, node, machine, 0))
00788 graphNodes.append('tcf1.tcfNode-%s'%i)
00789 apiSuccess(master.addNode('m', 'tcf2', 'tcfNode-%s'%i, pkg, node, machine, 0))
00790 graphNodes.append('tcf2.tcfNode-%s'%i)
00791 apiSuccess(master.addNode('m', 'tcf1.sub1', 'tcfNode-%s'%i, pkg, node, machine, 0))
00792 graphNodes.append('tcf1.sub1.tcfNode-%s'%i)
00793 apiSuccess(master.addNode('m', 'tcf2.sub1', 'tcfNode-%s'%i, pkg, node, machine, 0))
00794 graphNodes.append('tcf2.sub1.tcfNode-%s'%i)
00795 apiSuccess(master.addNode('m', 'tcf3', 'tcfNode3-%s'%i, pkg, node, machine, 0))
00796 graphNodes.append('tcf3.tcfNode3-%s'%i)
00797 testGraphState(master, graphNodes, graphFlows)
00798
00799 reliable = 1
00800
00801
00802 illegal = [
00803
00804 ['node.tcf1', 'baseTcfNode-1:out', 'tcfNode-1:in'],
00805 ['tcf1.node', 'tcfNode-1:out', 'baseTcfNode-1:in'],
00806 ['tcf1.tcfNode-1', 'tcfNode-1:out', 'tcf1.tcfNode-1:in'],
00807 ['tcf1.tcfNode-1', ':out', 'tcf1.tcfNode-1:in'],
00808 ['tcf1.tcfNode-1', 'tcf1.tcfNode-2:out', ':in'],
00809 ['tcf1.node', 'tcf1.tcfNode-1:out', 'tcfNode-1:in'],
00810 ['tcf1.node', 'tcf2.tcfNode-1:out', 'tcfNode-1:in'],
00811 ['tcf1.node', 'tcfNode-1:out', 'tcf2.tcfNode-1:in'],
00812 ['tcf1.node', 'sub1.tcfNode-1:out', 'tcf2.sub1.tcfNode-1:in'],
00813 ['tcf1.sub1.node','baseTcfNode-1:out', 'tcfNode-1:in'],
00814 ['tcf1.sub1.node','sub1.tcfNode-1:out', 'tcfNode-1:in'],
00815 ['tcf1.sub1.node','tcf2.tcfNode-1:out', 'tcfNode-1:in'],
00816 ]
00817 for callerId, source, sink in illegal:
00818 apiError(master.connectFlow(callerId, source, sink, reliable))
00819
00820
00821 singleCase = [
00822
00823 ['node', 'tcfNode-1:out', 'tcfNode-2:in', 'tcfNode-1:out', 'tcfNode-2:in',],
00824 ['tcfNode-1','tcf1.tcfNode-1:out', 'tcf1.tcfNode-2:in', 'tcf1.tcfNode-1:out', 'tcf1.tcfNode-2:in'],
00825 ['tcf2.tcfNode-1', 'tcfNode-1:out', 'tcfNode-2:in', 'tcf2.tcfNode-1:out', 'tcf2.tcfNode-2:in'],
00826 ['tcf1.tcfNode-2', 'sub1.tcfNode-1:out', 'sub1.tcfNode-2:in', 'tcf1.sub1.tcfNode-1:out', 'tcf1.sub1.tcfNode-2:in'],
00827 ['tcf2.tcfNode-1', 'tcfNode-1:out', 'sub1.tcfNode-1:in', 'tcf2.tcfNode-1:out', 'tcf2.sub1.tcfNode-1:in'],
00828
00829
00830 ['tcf2.sub1.tcfNode-1', '.:out', 'tcfNode-2:in', 'tcf2.sub1.tcfNode-1:out', 'tcf2.sub1.tcfNode-2:in'],
00831 ['tcf3.tcfNode3-2', 'tcfNode3-1:out', '.:in', 'tcf3.tcfNode3-1:out', 'tcf3.tcfNode3-2:in'],
00832 ]
00833 for callerId, source, sink, sourceFull, sinkFull in singleCase:
00834 apiSuccess(master.connectFlow(callerId, source, sink, reliable))
00835 graphFlows.append((sourceFull, sinkFull))
00836 testGraphState(master, graphNodes, graphFlows)
00837
00838
00839
00840 apiError(master.connectFlow('tcf2.node', 'tcfNode-1:out', 'tcfNode-2:in', reliable))
00841 apiError(master.connectFlow('node', 'tcf1.tcfNode-1:out', 'tcf1.tcfNode-2:in', reliable))
00842
00843
00844
00845
00846
00847 def testKillFlow(self):
00848 master = self.master
00849 if 0:
00850 master.killFlow(callerId, source, sink)
00851
00852 def testMisc(self):
00853 master = self.master
00854 assert master is not None, "master is None"
00855 masterUri = apiSuccess(master.getMasterUri(''))
00856 assert masterUri == apiSuccess(master.getMasterUri('a.different.id')), master.getMasterUri('a.different.id')
00857 assert (getMasterUri() == masterUri) or \
00858 (getMasterUriAlt() == masterUri), masterUri
00859
00860 pid = apiSuccess(master.getPid(''))
00861 assert pid == apiSuccess(master.getPid('a.different.id')), master.getPid('a.different.id')
00862
00863 apiError(master.getPid(0))
00864 apiError(master.getMasterUri(0))
00865
00866 try:
00867 master.shutdown('some.id')
00868 except:
00869 pass
00870 time.sleep(0.1)
00871 try:
00872 code, status, val = master.getPid('')
00873 assert code < 1, "Master is still running after shutdown"
00874 except:
00875 pass
00876
00877 def testMasterMain(argv, stdout, env):
00878 return msMain(argv, stdout, env, [ParamServerTestCase, MasterTestCase], singletest)
00879
00880 if __name__ == '__main__':
00881 testMasterMain(sys.argv, sys.stdout, os.environ)
00882
00883