def test_RoslaunchChild(self): # this is mainly a code coverage test to try and make sure that we don't # have any uninitialized references, etc... from roslaunch.child import ROSLaunchChild name = 'child-%s' % time.time() server_uri = 'http://unroutable:1234' c = ROSLaunchChild(self.run_id, name, server_uri) self.assertEquals(self.run_id, c.run_id) self.assertEquals(name, c.name) self.assertEquals(server_uri, c.server_uri) # - this check tests our assumption about c's process monitor field self.assertEquals(None, c.pm) self.assertEquals(None, c.child_server) # should be a noop c.shutdown() # create a new child to test _start_pm() and shutdown() c = ROSLaunchChild(self.run_id, name, server_uri) # - test _start_pm and shutdown logic c._start_pm() self.assert_(c.pm is not None) c.shutdown() # create a new child to test run() with a fake process # monitor. this requires an actual parent server to be running import roslaunch.config server = roslaunch.server.ROSLaunchParentNode( roslaunch.config.ROSLaunchConfig(), self.pmon) # - register a fake child with the server so that it accepts registration from ROSLaunchChild server.add_child(name, ChildProcessMock('foo')) try: server.start() self.assert_(server.uri, "server URI did not initialize") c = ROSLaunchChild(self.run_id, name, server.uri) c.pm = self.pmon # - run should speed through c.run() finally: server.shutdown('test done') # one final test for code completness: raise an exception during run() c = ROSLaunchChild(self.run_id, name, server_uri) def bad(): raise Exception('haha') # - violate some encapsulation here just to make sure the exception happens c._start_pm = bad try: # this isn't really a correctness test, this just manually # tests that the exception is logged c.run() except: pass
def test_ROSLaunchChildNode(self): from roslaunch.server import ROSLaunchChildNode from roslaunch.server import ChildROSLaunchProcess pmon = self.pmon import roslib.params try: # if there is a core up, we have to use its run id run_id = roslib.params.get_param('/run_id') except: run_id = 'foo-%s' % time.time() name = 'foo-bob' server_uri = 'http://localhost:12345' try: ROSLaunchChildNode(run_id, name, server_uri, None) self.fail("should not allow pm as None") except: pass try: ROSLaunchChildNode(run_id, name, 'http://bad_uri:0', pmon) self.fail("should not allow bad uri") except: pass n = ROSLaunchChildNode(run_id, name, server_uri, pmon) self.assertEquals(run_id, n.run_id) self.assertEquals(name, n.name) self.assertEquals(server_uri, n.server_uri) # tests for actual registration with server import roslaunch.config server = roslaunch.server.ROSLaunchParentNode( roslaunch.config.ROSLaunchConfig(), self.pmon) # - register a fake child with the server so that it accepts registration from ROSLaunchChild child_proc = ChildROSLaunchProcess('foo', [], {}) server.add_child(name, child_proc) try: server.start() self.assert_(server.uri, "server URI did not initialize") s = ServerProxy(server.uri) print "SERVER STARTED" # start the child n = ROSLaunchChildNode(run_id, name, server.uri, pmon) n.start() print "CHILD STARTED" self.assert_(n.uri, "child URI did not initialize") # verify registration print "VERIFYING REGISTRATION" self.assertEquals(child_proc.uri, n.uri) child_uri = 'http://fake-unroutable:1324' # - list children val = self._succeed(s.list_children()) self.assertEquals([n.uri], val) finally: print "SHUTTING DOWN" n.shutdown('test done') server.shutdown('test done')
def test_ROSLaunchParentNode(self): from roslaunch.server import ROSLaunchParentNode from roslaunch.server import ChildROSLaunchProcess from roslaunch.config import ROSLaunchConfig from roslaunch.pmon import ProcessListener rosconfig = ROSLaunchConfig() try: ROSLaunchParentNode(rosconfig, None) self.fail("should not allow pm as None") except: pass pmon = self.pmon n = ROSLaunchParentNode(rosconfig, pmon) self.assertEquals(rosconfig, n.rosconfig) self.assertEquals([], n.listeners) self.assertEquals({}, n.child_processes) self.assertEquals(n.handler.listeners, n.listeners) self.assertEquals(n.handler.child_processes, n.child_processes) # test add listener self.assertEquals(n.handler.listeners, n.listeners) l = ProcessListener() n.add_process_listener(l) self.assertEquals([l], n.listeners) self.assertEquals(n.handler.listeners, n.listeners) # now, lets make some xmlrpc calls against it import roslaunch.config server = roslaunch.server.ROSLaunchParentNode( roslaunch.config.ROSLaunchConfig(), self.pmon) # it's really dangerous for logging when both a parent and a # child are in the same process, so out of paranoia, clear the # logging handlers roslaunch.core.clear_printlog_handlers() roslaunch.core.clear_printerrlog_handlers() # - register a fake child with the server so that it accepts registration from ROSLaunchChild child_name = 'child-%s' % time.time() child_proc = ChildROSLaunchProcess('foo', [], {}) server.add_child(child_name, child_proc) try: server.start() self.assert_(server.uri, "server URI did not initialize") s = ServerProxy(server.uri) child_uri = 'http://fake-unroutable:1324' # - list children should be empty val = self._succeed(s.list_children()) self.assertEquals([], val) # - register val = self._succeed(s.register(child_name, child_uri)) self.assertEquals(1, val) # - list children val = self._succeed(s.list_children()) self.assertEquals([child_uri], val) finally: server.shutdown('test done')
def test_roslaunchChild(self): # this is mainly a code coverage test to try and make sure that we don't # have any uninitialized references, etc... from roslaunch.child import ROSLaunchChild name = 'child-%s'%time.time() server_uri = 'http://unroutable:1234' c = ROSLaunchChild(self.run_id, name, server_uri) self.assertEquals(self.run_id, c.run_id) self.assertEquals(name, c.name) self.assertEquals(server_uri, c.server_uri) # - this check tests our assumption about c's process monitor field self.assertEquals(None, c.pm) self.assertEquals(None, c.child_server) # should be a noop c.shutdown() # create a new child to test _start_pm() and shutdown() c = ROSLaunchChild(self.run_id, name, server_uri) # - test _start_pm and shutdown logic c._start_pm() self.assert_(c.pm is not None) c.shutdown() # create a new child to test run() with a fake process # monitor. this requires an actual parent server to be running import roslaunch.config server = roslaunch.server.ROSLaunchParentNode(roslaunch.config.ROSLaunchConfig(), self.pmon) # - register a fake child with the server so that it accepts registration from ROSLaunchChild server.add_child(name, ChildProcessMock('foo')) try: server.start() self.assert_(server.uri, "server URI did not initialize") c = ROSLaunchChild(self.run_id, name, server.uri) c.pm = self.pmon # - run should speed through c.run() finally: server.shutdown('test done') # one final test for code completness: raise an exception during run() c = ROSLaunchChild(self.run_id, name, server_uri) def bad(): raise Exception('haha') # - violate some encapsulation here just to make sure the exception happens c._start_pm = bad try: # this isn't really a correctness test, this just manually # tests that the exception is logged c.run() except: pass
def test_ROSLaunchChildNode(self): from roslaunch.server import ROSLaunchChildNode from roslaunch.server import ChildROSLaunchProcess pmon = self.pmon import roslib.params try: # if there is a core up, we have to use its run id run_id = roslib.params.get_param('/run_id') except: run_id = 'foo-%s'%time.time() name = 'foo-bob' server_uri = 'http://localhost:12345' try: ROSLaunchChildNode(run_id, name, server_uri, None) self.fail("should not allow pm as None") except: pass try: ROSLaunchChildNode(run_id, name, 'http://bad_uri:0', pmon) self.fail("should not allow bad uri") except: pass n = ROSLaunchChildNode(run_id, name, server_uri, pmon) self.assertEquals(run_id, n.run_id) self.assertEquals(name, n.name) self.assertEquals(server_uri, n.server_uri) # tests for actual registration with server import roslaunch.config server = roslaunch.server.ROSLaunchParentNode(roslaunch.config.ROSLaunchConfig(), self.pmon) # - register a fake child with the server so that it accepts registration from ROSLaunchChild child_proc = ChildROSLaunchProcess('foo', [], {}) server.add_child(name, child_proc) try: server.start() self.assert_(server.uri, "server URI did not initialize") s = ServerProxy(server.uri) print "SERVER STARTED" # start the child n = ROSLaunchChildNode(run_id, name, server.uri, pmon) n.start() print "CHILD STARTED" self.assert_(n.uri, "child URI did not initialize") # verify registration print "VERIFYING REGISTRATION" self.assertEquals(child_proc.uri, n.uri) child_uri = 'http://fake-unroutable:1324' # - list children val = self._succeed(s.list_children()) self.assertEquals([n.uri], val) finally: print "SHUTTING DOWN" n.shutdown('test done') server.shutdown('test done')
def test_ROSLaunchParentNode(self): from roslaunch.server import ROSLaunchParentNode from roslaunch.server import ChildROSLaunchProcess from roslaunch.config import ROSLaunchConfig from roslaunch.pmon import ProcessListener rosconfig = ROSLaunchConfig() try: ROSLaunchParentNode(rosconfig, None) self.fail("should not allow pm as None") except: pass pmon = self.pmon n = ROSLaunchParentNode(rosconfig, pmon) self.assertEquals(rosconfig, n.rosconfig) self.assertEquals([], n.listeners) self.assertEquals({}, n.child_processes) self.assertEquals(n.handler.listeners, n.listeners) self.assertEquals(n.handler.child_processes, n.child_processes) # test add listener self.assertEquals(n.handler.listeners, n.listeners) l = ProcessListener() n.add_process_listener(l) self.assertEquals([l], n.listeners) self.assertEquals(n.handler.listeners, n.listeners) # now, lets make some xmlrpc calls against it import roslaunch.config server = roslaunch.server.ROSLaunchParentNode(roslaunch.config.ROSLaunchConfig(), self.pmon) # it's really dangerous for logging when both a parent and a # child are in the same process, so out of paranoia, clear the # logging handlers roslaunch.core.clear_printlog_handlers() roslaunch.core.clear_printerrlog_handlers() # - register a fake child with the server so that it accepts registration from ROSLaunchChild child_name = 'child-%s'%time.time() child_proc = ChildROSLaunchProcess('foo', [], {}) server.add_child(child_name, child_proc) try: server.start() self.assert_(server.uri, "server URI did not initialize") s = ServerProxy(server.uri) child_uri = 'http://fake-unroutable:1324' # - list children should be empty val = self._succeed(s.list_children()) self.assertEquals([], val) # - register val = self._succeed(s.register(child_name, child_uri)) self.assertEquals(1, val) # - list children val = self._succeed(s.list_children()) self.assertEquals([child_uri], val) finally: server.shutdown('test done')