test_pull_remotely.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #       
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_multimaster/master/rocon_gateway_tests/LICENSE 
00005 #
00006 
00007 PKG = 'rocon_gateway_tests'
00008 import roslib; roslib.load_manifest(PKG)
00009 import rospy
00010 import rostest
00011 from gateway_msgs.msg import *
00012 from gateway_msgs.srv import *
00013 from rocon_gateway.master_api import LocalMaster
00014 import unittest
00015 import std_msgs
00016 import copy
00017 
00018 class TestPullRemotely(unittest.TestCase):
00019 
00020     def assertRemotePublicInterface(self, gateway_name, rules):
00021 
00022         expected_rules = copy.deepcopy(rules)
00023         num_nodes = len(expected_rules)
00024         while True:
00025             rospy.sleep(1.0)
00026             resp = self.remoteGatewayInfo()
00027             remote_gateway = None
00028             for gateway in resp.gateways:
00029                 if gateway.name == gateway_name:
00030                     remote_gateway = gateway
00031                     break
00032             self.assertIsNotNone(remote_gateway)
00033             node_names = []
00034             for i in remote_gateway.public_interface:
00035                 node_names.append(i.node)
00036             rospy.loginfo("TEST: Public Interface Nodes (Gateway: %s): %s"%(gateway_name, str(node_names)))
00037             if len(remote_gateway.public_interface) == num_nodes:
00038                 break
00039             rospy.loginfo("TEST:   Waiting for watcher thread to load all nodes.")
00040 
00041         for i in range(num_nodes):
00042             self.assertIn(remote_gateway.public_interface[i], expected_rules)
00043             expected_rules.remove(remote_gateway.public_interface[i])
00044 
00045         self.assertEqual(len(expected_rules), 0);
00046         rospy.loginfo("TEST: Public interface for %s found as expected"%gateway_name)
00047 
00048     def assertMasterState(self, expected_interface):
00049         while True:
00050             rospy.sleep(1.0)
00051             connection_state = self.master.getConnectionState()
00052             all_rules_found = True
00053             rules_not_found = []
00054             for rule in expected_interface:
00055                 rule_type = rule[0]
00056                 rule_name = rule[1]
00057                 rule_count = rule[2]
00058                 num_rules_found = 0
00059                 for connection in connection_state[rule_type]:
00060                     if connection.rule.name == rule_name:
00061                         num_rules_found = num_rules_found + 1
00062                 if num_rules_found != rule_count:
00063                     rules_not_found.append(rule_name)
00064                     all_rules_found = False
00065             if all_rules_found:
00066                 break
00067             rospy.log_info("TEST: Following rules found with incorrect number of instances: %s"%str(rules_not_found))
00068 
00069         rospy.loginfo("TEST: Master state found as expected")
00070 
00071     def assertPullCall(self, watchlist, expected_interface):
00072 
00073         zero_interface = []
00074         for i in expected_interface:
00075             zero_interface.append((i[0],i[1],0))
00076 
00077         self.assertMasterState(zero_interface)
00078 
00079         for remote_rule in watchlist:
00080             req = RemoteRequest()
00081             req.remotes.append(remote_rule)
00082             req.cancel = False
00083 
00084             resp = self.pull(req)
00085             self.assertEquals(resp.result, Result.SUCCESS)
00086 
00087         self.assertMasterState(expected_interface)
00088             
00089         for remote_rule in watchlist:
00090             req = RemoteRequest()
00091             req.remotes.append(remote_rule)
00092             req.cancel = True
00093 
00094             resp = self.pull(req)
00095             self.assertEquals(resp.result, Result.SUCCESS)
00096 
00097         self.assertMasterState(zero_interface)
00098 
00099     def assertPullAllCall(self, gateway, blacklist, expected_interface):
00100 
00101         zero_interface = []
00102         for i in expected_interface:
00103             zero_interface.append((i[0],i[1],0))
00104 
00105         self.assertMasterState(zero_interface)
00106 
00107         req = RemoteAllRequest()
00108         req.gateway = gateway
00109         req.blacklist = blacklist
00110         req.cancel = False
00111         resp = self.pullAll(req)
00112         self.assertEquals(resp.result, Result.SUCCESS)
00113 
00114         self.assertMasterState(expected_interface)
00115             
00116         req = RemoteAllRequest()
00117         req.gateway = gateway
00118         req.cancel = True
00119         resp = self.pullAll(req)
00120         self.assertEquals(resp.result, Result.SUCCESS)
00121 
00122         self.assertMasterState(zero_interface)
00123 
00124 
00125     def setUp(self):
00126         '''
00127           Run at the start of every test. This function performs the following:
00128             1. Ensure that gateway services are available
00129             2. Make sure gateway is connected to the hub
00130           If something goes wrong and the setup can not complete successfully,
00131           the test will timeout with an error
00132         '''
00133         rospy.wait_for_service('/gateway/pull')
00134         rospy.wait_for_service('/gateway/pull_all')
00135         rospy.wait_for_service('/gateway/gateway_info')
00136         rospy.wait_for_service('/gateway/remote_gateway_info')
00137 
00138         self.pull = rospy.ServiceProxy('/gateway/pull', Remote)
00139         self.pullAll = rospy.ServiceProxy('/gateway/pull_all', RemoteAll)
00140         self.gatewayInfo = rospy.ServiceProxy('/gateway/gateway_info', GatewayInfo)
00141         self.remoteGatewayInfo = rospy.ServiceProxy('/gateway/remote_gateway_info', RemoteGatewayInfo)
00142 
00143         # Make sure we are connected to the gateway first!
00144         while True:
00145             rospy.sleep(1.0)
00146             resp = self.gatewayInfo()
00147             if resp.connected:
00148                 break
00149             rospy.loginfo("TEST: Waiting for local gateway to be connected...")
00150 
00151         rospy.loginfo("TEST: Local gateway connected")
00152 
00153         # Wait for remote gateway to come up
00154         req = RemoteGatewayInfoRequest()
00155         req.gateways = []
00156         while True:
00157             rospy.sleep(1.0)
00158             resp = self.remoteGatewayInfo(req)
00159             self.assertLessEqual(len(resp.gateways), 1)
00160             if len(resp.gateways) == 0:
00161                 rospy.loginfo("TEST: Waiting for remote gateway to come up...")
00162             else:
00163                 self.remote_gateway_name = resp.gateways[0].name
00164                 break
00165 
00166         rospy.loginfo("TEST: Remote gateway connected")
00167 
00168         self.master = LocalMaster()
00169         # unit test property - show the difference when an assertion fails
00170         self.maxDiff = None
00171 
00172     def test_checkRemotePublicInterface(self):
00173         '''
00174           Makes sure that every connection type is being detected and advertised
00175           appropriately.
00176         '''
00177         expected_interface = []
00178         expected_interface.append(Rule(ConnectionType.PUBLISHER, "/chatter", "/talker"))
00179         expected_interface.append(Rule(ConnectionType.PUBLISHER, "/chatter", "/talker2"))
00180         expected_interface.append(Rule(ConnectionType.SUBSCRIBER, "/chatter", "/listener"))
00181         expected_interface.append(Rule(ConnectionType.SUBSCRIBER, "/random_number", "/averaging_server"))
00182         expected_interface.append(Rule(ConnectionType.SERVICE, "/add_two_ints", "/add_two_ints_server"))
00183         expected_interface.append(Rule(ConnectionType.ACTION_SERVER, "/averaging_server/", "/averaging_server"))
00184         expected_interface.append(Rule(ConnectionType.ACTION_CLIENT, "/fibonacci/", "/fibonacci_client"))
00185         self.assertRemotePublicInterface(self.remote_gateway_name, expected_interface)
00186 
00187     def test_pullPublisherByTopic(self):
00188         watchlist = [RemoteRule(self.remote_gateway_name, Rule(ConnectionType.PUBLISHER, "/chatter", ''))]
00189         expected_interface = [(ConnectionType.PUBLISHER, "/chatter", 2)]
00190         self.assertPullCall(watchlist, expected_interface)
00191 
00192         # Test topic name using regex
00193         watchlist = [RemoteRule(self.remote_gateway_name, Rule(ConnectionType.PUBLISHER, "/chat.*", ''))]
00194         self.assertPullCall(watchlist, expected_interface)
00195 
00196     def test_pullPublisherByNode(self):
00197         watchlist = [RemoteRule(self.remote_gateway_name, Rule(ConnectionType.PUBLISHER, "/chatter", "/talker"))]
00198         expected_interface = [(ConnectionType.PUBLISHER, "/chatter", 1)]
00199         self.assertPullCall(watchlist, expected_interface)
00200 
00201         # Test using regex
00202         watchlist = [RemoteRule(self.remote_gateway_name, Rule(ConnectionType.PUBLISHER, "/chat.*", ".*ker"))]
00203         self.assertPullCall(watchlist, expected_interface)
00204 
00205     def test_pullDifferentConnections(self):
00206         topics = {}
00207         topics[ConnectionType.PUBLISHER] = "/chatter"
00208         topics[ConnectionType.SUBSCRIBER] = "/chatter"
00209         topics[ConnectionType.SERVICE] = "/add_two_ints"
00210         topics[ConnectionType.ACTION_SERVER] = "/averaging_server/"
00211         topics[ConnectionType.ACTION_CLIENT] = "/fibonacci/"
00212         nodes = {}
00213         nodes[ConnectionType.PUBLISHER] = ["/talker","/talker2"]
00214         nodes[ConnectionType.SUBSCRIBER] = ["/listener"]
00215         nodes[ConnectionType.SERVICE] = ["/add_two_ints_server"]
00216         nodes[ConnectionType.ACTION_SERVER] = ["/averaging_server"]
00217         nodes[ConnectionType.ACTION_CLIENT] = ["/fibonacci_client"]
00218 
00219         watchlist = [RemoteRule(self.remote_gateway_name, Rule(type, topics[type], '')) for type in topics]
00220         expected_interface = [(type, topics[type], len(nodes[type])) for type in topics]
00221         self.assertPullCall(watchlist, expected_interface)
00222 
00223     def test_pullAll(self):
00224         topics = {}
00225         topics[ConnectionType.PUBLISHER] = "/chatter"
00226         topics[ConnectionType.SUBSCRIBER] = "/chatter"
00227         topics[ConnectionType.SERVICE] = "/add_two_ints"
00228         topics[ConnectionType.ACTION_SERVER] = "/averaging_server/"
00229         topics[ConnectionType.ACTION_CLIENT] = "/fibonacci/"
00230         nodes = {}
00231         nodes[ConnectionType.PUBLISHER] = ["/talker","/talker2"]
00232         nodes[ConnectionType.SUBSCRIBER] = ["/listener"]
00233         nodes[ConnectionType.SERVICE] = ["/add_two_ints_server"]
00234         nodes[ConnectionType.ACTION_SERVER] = ["/averaging_server"]
00235         nodes[ConnectionType.ACTION_CLIENT] = ["/fibonacci_client"]
00236 
00237         blacklist = []
00238         expected_interface = [(type, topics[type], len(nodes[type])) for type in topics]
00239         expected_interface.append((ConnectionType.SUBSCRIBER, "/random_number", 1))
00240         self.assertPullAllCall(self.remote_gateway_name, blacklist, expected_interface)
00241 
00242     def tearDown(self):
00243         '''
00244           Called at the end of every test to ensure that all the advertisements
00245           are removed
00246         '''
00247         pass
00248 
00249 if __name__ == '__main__':
00250     rospy.init_node('multimaster_test')
00251     rostest.rosrun(PKG, 'test_pull_remotely', TestPullRemotely) 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rocon_gateway_tests
Author(s): Jihoon
autogenerated on Tue Jan 15 2013 17:44:10