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