Esempio n. 1
0
 def setUp(self):
     self.osm_bridge = OSMBridge()
     # self.global_origin = [50.7800401, 7.18226]  # uni (coordinates of node id 1307)
     # self.osm_bridge = OSMBridge(global_origin=self.global_origin)
     self.global_path_planner = GlobalPathPlanner(self.osm_bridge)
     self.navigation_path_planner = NavigationPathPlanner(self.osm_bridge)
     self.semantic_global_path = None
class OSMNetworkCreator(object):
    """Create a graph for an OSM floor at area level"""
    def __init__(self, lat, lon, building, floor):
        self.osm_bridge = OSMBridge(
            global_origin=[REF_LATITUDE, REF_LONGITUDE])
        self.floor = self.osm_bridge.get_floor(building + '_L' + str(floor))

    def build_graph(self):
        nodes = []
        node_ids = []
        connections = []
        connection_ids = self.floor.connection_ids
        connection_ids.extend(
            self.floor._member_ids['global_connection_blocked']
            if 'global_connection_blocked' in self.floor._member_ids else [])
        for connection_id in connection_ids:
            connection = self.osm_bridge.get_connection(connection_id)
            connection_list = connection.point_ids

            if len(connection_list) == 2:
                connections.append(connection_list)
            else:
                for i in range(len(connection_list) - 1):
                    connections.append(
                        [connection_list[i], connection_list[i + 1]])

            for point in connection.points:
                node = self.get_node_from_point(point)
                if node.id not in node_ids:
                    node_ids.append(node.id)
                    nodes.append(node)
        print('Nodes found:', len(nodes))
        print('Edges found:', len(connections))
        self.write_in_yaml(nodes, connections)
        print('Writing info in /tmp/osm_network.yaml')

    def write_in_yaml(self, nodes, connections):
        with open('/tmp/osm_network.yaml', 'w') as file_obj:
            node_dict = [node.to_dict() for node in nodes]
            yaml.dump({'nodes': node_dict}, file_obj, default_flow_style=False)
            yaml.dump({'connections': connections},
                      file_obj,
                      default_flow_style=True)

    def get_node_from_point(self, point):
        _, _, relations = point.osm_adapter.get_parent(
            id=point.id, data_type='node', parent_child_role='topology')
        relation = relations[0]
        area_name, area_type = None, None
        for tag in relations[0].tags:
            if tag.key == "type":
                area_type = tag.value
            if tag.key == "ref":
                area_name = tag.value
        n = Node(point.id, point.x, point.y, area_name, area_type)
        return n
class TestComputeOrientation(unittest.TestCase):

    @classmethod
    def setUpClass(cls):
        pass

    @classmethod
    def tearDownClass(cls):
        pass

    def setUp(self):
        self.osm_bridge = OSMBridge(server_ip='172.16.1.101', server_port=8000, global_origin=[
                                    50.7800401, 7.18226], coordinate_system='cartesian')
        self.compute_orientation = ComputeOrientation()

    def tearDown(self):
        pass

    def test_compute_center(self):
        corridor = self.osm_bridge.get_corridor('BRSU_C_L0_C9')
        pt = self.compute_orientation._compute_center(corridor.geometry.points)
        print(pt)

    def test_get_nearest_points(self):
        prev_area = self.osm_bridge.get_corridor('BRSU_C_L0_C5')
        curr_area = self.osm_bridge.get_corridor('BRSU_C_L0_C6')
        pts = self.compute_orientation._get_nearest_points(
            prev_area, curr_area)
        print(pts)

    def test_compute_corridor_orientation(self):
        prev_area = self.osm_bridge.get_corridor('BRSU_C_L0_C5')
        curr_area = self.osm_bridge.get_corridor('BRSU_C_L0_C6')
        next_area = self.osm_bridge.get_corridor('BRSU_C_L0_C7')
        angle = self.compute_orientation.get_corridor_orientation(
            prev_area, curr_area, next_area)
        print(angle)

    def test_get_door_points(self):
        door = self.osm_bridge.get_door('BRSU_C_L0_RoomC022_Door1')
        pts = self.compute_orientation._get_door_points(door.geometry.points)
        print(pts)

    def test_get_door_orientation1(self):
        door = self.osm_bridge.get_door('BRSU_C_L0_RoomC022_Door1')
        corridor = self.osm_bridge.get_corridor('BRSU_C_L0_C9')
        angle = self.compute_orientation.get_door_orientation(door, corridor)
        print(angle)

    def test_get_door_orientation2(self):
        door = self.osm_bridge.get_door('BRSU_C_L0_RoomC022_Door1')
        room = self.osm_bridge.get_room('BRSU_C_L0_RoomC022')
        angle = self.compute_orientation.get_door_orientation(door, room)
        print(angle)
Esempio n. 4
0
    def __init__(self):
        server_ip = rospy.get_param('~overpass_server_ip')
        server_port = rospy.get_param('~overpass_server_port')
        ref_lat = rospy.get_param('~ref_latitude')
        ref_lon = rospy.get_param('~ref_longitude')
        building = rospy.get_param('~building')
        global_origin = [ref_lat, ref_lon]

        rospy.loginfo("Server " + server_ip + ":" + str(server_port))
        rospy.loginfo("Global origin: " + str(global_origin))
        rospy.loginfo("Starting servers...")


        self.osm_topological_planner_server = SimpleActionServer(
            '/osm_topological_planner', OSMTopologicalPlannerAction, self._osm_topological_planner, False)
        self.osm_topological_planner_server.start()

        osm_bridge = OSMBridge(
            server_ip=server_ip,
            server_port=server_port,
            global_origin=global_origin,
            coordinate_system="cartesian",
            debug=False)
        path_planner = PathPlanner(osm_bridge)
        path_planner.set_building(building)
        self.osm_topological_planner_callback = OSMTopologicalPlannerCallback(
            osm_bridge, path_planner)
        rospy.loginfo(
            "OSM topological planner server started. Listening for requests...")
    def __init__(self):
        server_ip = rospy.get_param('~overpass_server_ip')
        server_port = rospy.get_param('~overpass_server_port')
        ref_lat = rospy.get_param('~ref_latitude')
        ref_lon = rospy.get_param('~ref_longitude')
        map_dimension = rospy.get_param('~map_dimension')
        global_origin = [ref_lat, ref_lon]

        rospy.loginfo("Server " + server_ip + ":" + str(server_port))
        rospy.loginfo("Global origin: " + str(global_origin))
        rospy.loginfo("Starting servers...")

        self.osm_bridge = OSMBridge(server_ip=server_ip,
                                    server_port=server_port,
                                    global_origin=global_origin,
                                    coordinate_system="cartesian",
                                    debug=False)

        self.osm_adapter = OSMAdapter(server_ip=server_ip,
                                      server_port=server_port,
                                      global_origin=global_origin,
                                      coordinate_system="cartesian",
                                      debug=False)

        self.semantic_features_finder = SemanticFeaturesFinder(self.osm_bridge)

        if map_dimension == '3D':
            self.get_map = Get3DMap(self.osm_bridge,
                                    self.semantic_features_finder)
        elif map_dimension == '2D':
            self.get_map = Get2DMap(self.osm_bridge, self.osm_adapter,
                                    self.semantic_features_finder)
        else:
            rospy.logerr("Please specify correct map dimension")

        self.get_geometric_map_server = rospy.Service('/get_geometric_map',
                                                      GetGeometricMap,
                                                      self._get_geometric_map)
        rospy.loginfo(
            "Get geometric map server started. Listening for queries...")

        self.get_semantic_map_server = rospy.Service('/get_semantic_map',
                                                     GetSemanticMap,
                                                     self._get_semantic_map)
        rospy.loginfo(
            "Get semantic map server started. Listening for queries...")

        self.geometric_map_pub = rospy.Publisher('/geometric_map',
                                                 GeometricMap,
                                                 queue_size=10,
                                                 latch=True)
        self.semantic_map_pub = rospy.Publisher('/semantic_map',
                                                SemanticMap,
                                                queue_size=10,
                                                latch=True)
Esempio n. 6
0
    def __init__(self):
        server_ip = rospy.get_param('~overpass_server_ip')
        server_port = rospy.get_param('~overpass_server_port')
        ref_lat = rospy.get_param('~ref_latitude')
        ref_lon = rospy.get_param('~ref_longitude')
        building = rospy.get_param('~building')
        global_origin = [ref_lat, ref_lon]
        print(building)

        rospy.loginfo("Server " + server_ip + ":" + str(server_port))
        rospy.loginfo("Global origin: " + str(global_origin))
        rospy.loginfo("Starting servers...")

        self.osm_bridge = OSMBridge(
                server_ip=server_ip,
                server_port=server_port,
                global_origin=global_origin,
                coordinate_system="cartesian",
                debug=False)
        self.osm_adapter = OSMAdapter(
                server_ip=server_ip,
                server_port=server_port,
                debug=False)
        self.occ_grid_generator = OccGridGenerator(
                server_ip=server_ip,
                server_port=server_port,
                global_origin=global_origin,
                debug=False)

        self.wm_query_server = SimpleActionServer('/wm_query', WMQueryAction, self._wm_query, False)
        self.wm_query_server.start()
        self.wm_query_callback = WMQueryCallback(self.osm_bridge)

        self.osm_query_server = SimpleActionServer('/osm_query', OSMQueryAction, self._osm_query, False)
        self.osm_query_server.start()
        self.osm_query_callback = OSMQueryCallback(self.osm_adapter)

        self.path_planner_server = SimpleActionServer('/path_planner', PathPlannerAction, self._path_planner, False)
        self.path_planner = PathPlanner(self.osm_bridge)
        self.path_planner.set_building(building)
        self.path_planner_server.start()

        self.semantic_features_server = SimpleActionServer('/semantic_features', SemanticFeaturesAction, self._semantic_features, False)
        self.semantic_features_finder = SemanticFeaturesFinder(self.osm_bridge)
        self.semantic_features_server.start()
        self.semantic_features_callback = SemanticFeaturesCallback(self.semantic_features_finder)

        self.grid_map_generator_server = SimpleActionServer('/grid_map_generator', GridMapGeneratorAction, self._grid_map_generator, False)
        self.grid_map_generator_server.start()

        self.nearest_wlan_server = SimpleActionServer('/nearest_wlan', NearestWLANAction, self._nearest_wlan, False)
        self.nearest_wlan_finder = NearestWLANFinder(self.osm_bridge)
        self.nearest_wlan_server.start()

        rospy.loginfo("Servers started. Listening for queries...")
    def setUp(self):
        self.osm_bridge = OSMBridge()
        self.server_ip = "127.0.0.1"
        self.server_port = 8000
        #self.global_origin = [50.1363485, 8.6474024]  # amk
        self.global_origin = [50.7800401, 7.18226]  # uni

        #self.local_offset = [25, 25]  # amk
        self.local_offset = [25, 80] # brsu

        self.debug = False
    def setUp(self):
        self.osm_bridge = OSMBridge()
        self.server_ip = "127.0.0.1"
        self.server_port = 8000
        #self.global_origin = [50.1363485, 8.6474024]  # amk
        #self.global_origin = [50.7800401, 7.18226]  # uni (coordinates of node id 1307)
        self.global_origin = [48.6938905,
                              9.1902848]  # logimat (coordinates of node id 57)

        #self.local_offset = [25, 25]  # amk
        #self.local_offset = [110, 80] # brsu
        self.local_offset = [10, 10]  # logimat
        self.floor = 0
        self.debug = False
Esempio n. 9
0
 def setUp(self):
     self.global_origin = [50.7800401,
                           7.18226]  # uni (coordinates of node id 1307)
     self.osm_bridge = OSMBridge(global_origin=self.global_origin)
     self.wlan_finder = NearestWLANFinder(self.osm_bridge)
     self.floor_name = 'BRSU_L0'
Esempio n. 10
0
class TestPathPlanner(unittest.TestCase):
    def setUp(self):
        self.osm_bridge = OSMBridge()
        # self.global_origin = [50.7800401, 7.18226]  # uni (coordinates of node id 1307)
        # self.osm_bridge = OSMBridge(global_origin=self.global_origin)
        self.global_path_planner = GlobalPathPlanner(self.osm_bridge)
        self.navigation_path_planner = NavigationPathPlanner(self.osm_bridge)
        self.semantic_global_path = None

    def test_global_plan_same_floor_plus_local_planner(self):
        building = self.osm_bridge.get_building('AMK')
        start_floor = self.osm_bridge.get_floor('AMK_L-1')
        destination_floor = self.osm_bridge.get_floor('AMK_L-1')
        start = self.osm_bridge.get_corridor('AMK_B_L-1_C1')
        destination = self.osm_bridge.get_corridor('AMK_D_L-1_C41')
        global_path = self.global_path_planner.plan(start_floor,
                                                    destination_floor, start,
                                                    destination,
                                                    building.elevators)

        start_local = self.osm_bridge.get_local_area('AMK_D_L-1_C41_LA1')
        destination_local = self.osm_bridge.get_local_area('AMK_B_L-1_C2_LA1')
        path = self.navigation_path_planner.plan(start_floor,
                                                 destination_floor,
                                                 start_local,
                                                 destination_local,
                                                 global_path)

    def test_global_plan_different_floors_plus_local_planner(self):
        building = self.osm_bridge.get_building('AMK')
        start_floor = self.osm_bridge.get_floor('AMK_L-1')
        destination_floor = self.osm_bridge.get_floor('AMK_L4')

        start_global = self.osm_bridge.get_corridor('AMK_D_L-1_C41')
        destination_global = self.osm_bridge.get_corridor('AMK_B_L4_C1')

        global_path = self.global_path_planner.plan(start_floor,
                                                    destination_floor,
                                                    start_global,
                                                    destination_global,
                                                    building.elevators)

        start_local = self.osm_bridge.get_local_area('AMK_D_L-1_C41_LA1')
        destination_local = self.osm_bridge.get_local_area('AMK_B_L4_C1_LA1')
        path = self.navigation_path_planner.plan(start_floor,
                                                 destination_floor,
                                                 start_local,
                                                 destination_local,
                                                 global_path)

        # for pt in path:
        #     print(pt)
        #     print(pt.exit_door)
        #     print(pt.navigation_areas)
        #     print("---------------------------------------------")
        # self.assertEqual(path[1].id, 119)
        self.assertEqual(len(path), 27)

    def test_overall_path_planner(self):
        path_planner = PathPlanner(self.osm_bridge)
        path_planner.set_building('AMK')
        path = path_planner.get_path_plan(
            start_floor='AMK_L-1',
            destination_floor='AMK_L4',
            start_area='AMK_D_L-1_C41',
            destination_area='AMK_B_L4_C1',
            start_local_area='AMK_D_L-1_C41_LA1',
            destination_local_area='AMK_B_L4_C1_LA1')
        print(path)
        self.assertEqual(path[1].id, 119)
        self.assertEqual(len(path), 27)

    # def test_overall_path_planner(self):
    #     path_planner = PathPlanner(self.osm_bridge)
    #     path_planner.set_building('BRSU')
    #     path = path_planner.get_path_plan(
    #             destination_floor='BRSU_L0',
    #             start_floor='BRSU_L0',
    #             start_area='BRSU_C_L0_C9',
    #             start_local_area='BRSU_C_L0_C9_LA1',
    #             destination_area='BRSU_A_L0_C9',
    #             destination_local_area='BRSU_C_L0_C9_LA2'
    #             )
    #     print(path)

    def test_dynamic_path_planner_blocked_with_traffic_rules(self):
        path_planner = PathPlanner(self.osm_bridge)
        path_planner.set_building('AMK')

        # path planning should fail here as connections are blocked and traffic rules are
        # still in effect
        with self.assertRaises(Exception) as context:
            self.assertRaises(
                path_planner.get_path_plan(
                    start_floor='AMK_L-1',
                    destination_floor='AMK_L4',
                    start_area='AMK_D_L-1_C41',
                    destination_area='AMK_B_L4_C1',
                    start_local_area='AMK_D_L-1_C41_LA1',
                    destination_local_area='AMK_B_L4_C1_LA1',
                    blocked_connections=[[
                        'AMK_C_L-1_C36_LA2', 'AMK_C_L-1_C35_LA2'
                    ], ['AMK_C_L-1_C35_LA2', 'AMK_C_L-1_C34_Door1']],
                    relax_traffic_rules=False))
        self.assertTrue("Couldn't plan the path" in str(context.exception))

    def test_dynamic_path_planner_blocked_wo_traffic_rules(self):
        path_planner = PathPlanner(self.osm_bridge)
        path_planner.set_building('AMK')

        try:
            # even though connections are blocked since traffic rules are relaxed
            # path planning should be successful in this case
            path_planner.get_path_plan(
                start_floor='AMK_L-1',
                destination_floor='AMK_L4',
                start_area='AMK_D_L-1_C41',
                destination_area='AMK_B_L4_C1',
                start_local_area='AMK_D_L-1_C41_LA1',
                destination_local_area='AMK_B_L4_C1_LA1',
                blocked_connections=[[
                    'AMK_C_L-1_C36_LA2', 'AMK_C_L-1_C35_LA2'
                ], ['AMK_C_L-1_C35_LA2', 'AMK_C_L-1_C34_Door1']],
                relax_traffic_rules=True)
        except:
            self.fail("In this case path shhould be successfully planned")

    def test_get_estimated_path_distance(self):
        path_planner = PathPlanner(self.osm_bridge)
        path_planner.set_building('AMK')

        try:
            # even though connections are blocked since traffic rules are relaxed
            # path planning should be successful in this case
            distance = path_planner.get_estimated_path_distance(
                start_floor='AMK_L-1',
                destination_floor='AMK_L4',
                start_area='AMK_D_L-1_C41',
                destination_area='AMK_B_L4_C1')
            print("Path distance:", distance)
        except:
            self.fail("In this case path shhould be successfully planned")
Esempio n. 11
0
 def setUp(self):
     self.osm_bridge = OSMBridge()
     self.osm_adapter = OSMAdapter()
Esempio n. 12
0
class TestOSMBridge(unittest.TestCase):
    def setUp(self):
        self.osm_bridge = OSMBridge()
        self.osm_adapter = OSMAdapter()

    def test_point(self):
        node_result, __, __ = self.osm_adapter.get_osm_element_by_id(
            ids=[4865], data_type='node')
        Point.coordinate_system = 'spherical'
        p = self.osm_bridge.get_point(node_result[0])
        assert p.lat is not None
        assert p.lon is not None
        assert p.x is not None
        assert p.y is not None

        # point by id
        p = self.osm_bridge.get_point(4865)
        assert p.id == 4865

    def test_shape(self):
        # point by id
        s = self.osm_bridge.get_shape(1021)
        assert len(s.points) > 0

    def test_get_feature_by_id(self):
        f = self.osm_bridge.get_feature(4865)
        self.assertEqual(f.id, 4865)

    def test_get_side_by_id(self):
        self.assertRaises(Exception, self.osm_bridge.get_side, 99999)

    def test_get_door_by_id(self):
        d = self.osm_bridge.get_door(161)
        self.assertEqual(d.id, 161)
        assert d.geometry is not None
        assert d.topology is not None
        assert d.sides is None

    def test_get_door_by_name(self):
        d = self.osm_bridge.get_door('AMK_B_L-1_C2_Door1')
        self.assertEqual(d.id, 161)
        assert d.geometry is not None
        assert d.topology is not None
        assert d.sides is None

    def test_get_door_from_point(self):
        node_result, __, __ = self.osm_adapter.get_osm_element_by_id(
            ids=[4978], data_type='node')
        Point.coordinate_system = 'cartesian'
        Point.global_origin = [50.1363485, 8.6474024]
        p = Point(node_result[0])
        d = self.osm_bridge.get_door(p)
        self.assertEqual(d.id, 150)

    def test_get_wall_by_id(self):
        self.assertRaises(Exception, self.osm_bridge.get_wall, 99999)

    def test_get_local_area_by_id(self):
        l = self.osm_bridge.get_local_area(173)
        assert l.id == 173
        assert l.geometry is not None
        assert l.topology is not None

    def test_get_local_area_by_name(self):
        l = self.osm_bridge.get_local_area('AMK_B_L4_RoomB404_LA2')
        assert l.id == 173
        assert l.geometry is not None
        assert l.topology is not None

    def test_get_local_area_from_point(self):
        node_result, __, __ = self.osm_adapter.get_osm_element_by_id(
            ids=[4743], data_type='node')
        Point.coordinate_system = 'cartesian'
        Point.global_origin = [50.1363485, 8.6474024]
        p = Point(node_result[0])
        l = self.osm_bridge.get_local_area(p)
        self.assertEqual(l.id, 27)

    def test_get_connection_by_id(self):
        c = self.osm_bridge.get_connection(1199)
        assert c.id == 1199
        assert len(c.points) > 0

    def test_get_room_by_id(self):
        r = self.osm_bridge.get_room(22)
        assert r.id == 22
        assert r.walls is None
        assert r.doors is not None
        assert r.local_areas is not None
        assert r.connections is not None
        assert r.geometry is not None
        assert r.topology is not None

    def test_get_room_by_ref(self):
        r = self.osm_bridge.get_room('AMK_B_L4_RoomB401')
        assert r.id == 22
        assert r.walls is None
        assert r.doors is not None
        assert r.local_areas is not None
        assert r.connections is not None
        assert r.geometry is not None
        assert r.topology is not None

    def test_get_room_from_point(self):
        node_result, __, __ = self.osm_adapter.get_osm_element_by_id(
            ids=[4678], data_type='node')
        Point.coordinate_system = 'cartesian'
        Point.global_origin = [50.1363485, 8.6474024]
        p = Point(node_result[0])
        r = self.osm_bridge.get_room(p)
        self.assertEqual(r.id, 22)

    def test_get_corridor_by_id(self):
        r = self.osm_bridge.get_corridor(140)
        assert r.id == 140
        assert r.walls is None
        assert r.doors is None
        assert r.local_areas is not None
        assert r.connections is not None
        assert r.geometry is not None
        assert r.topology is not None

    def test_get_corridor_by_ref(self):
        r = self.osm_bridge.get_corridor('AMK_B_L-1_C14')
        assert r.id == 140
        assert r.walls is None
        assert r.doors is None
        assert r.local_areas is not None
        assert r.connections is not None
        assert r.geometry is not None
        assert r.topology is not None

    def test_get_corridor_from_point(self):
        node_result, __, __ = self.osm_adapter.get_osm_element_by_id(
            ids=[4666], data_type='node')
        Point.coordinate_system = 'cartesian'
        Point.global_origin = [50.1363485, 8.6474024]
        p = Point(node_result[0])
        c = self.osm_bridge.get_corridor(p)
        self.assertEqual(c.id, 14)

    def test_get_elevator_by_id(self):
        e = self.osm_bridge.get_elevator(5)
        assert e.id == 5
        assert e.walls is None
        assert e.doors is None
        assert e.local_areas is not None
        assert e.connections is not None
        assert e.geometry is not None
        assert e.topology is not None

    def test_get_elevator_by_name(self):
        e = self.osm_bridge.get_elevator('AMK_B_E1')
        assert e.id == 5
        assert e.walls is None
        assert e.doors is None
        assert e.local_areas is not None
        assert e.connections is not None
        assert e.geometry is not None
        assert e.topology is not None

    def test_search_by_scope_for_elevator(self):
        e = self.osm_bridge.get_elevator('AMK_B_E1')
        assert e.id == 5
        la = e.local_area('AMK_B_E1_LA1')
        assert la.id == 163

    def test_get_floor(self):
        f = self.osm_bridge.get_floor(164)
        assert f.id == 164
        assert f.walls is None
        assert f.corridors is not None
        assert f.rooms is not None
        assert f.connections is not None

    def test_get_floor_by_name(self):
        f = self.osm_bridge.get_floor('AMK_L4')
        assert f.id == 164
        assert f.walls is None
        assert f.corridors is not None
        assert f.rooms is not None
        assert f.connections is not None

    def test_search_by_scope_for_floor(self):
        f = self.osm_bridge.get_floor('AMK_L4')
        r = f.room('AMK_B_L4_RoomB401')
        assert r.id == 22

        c = f.corridor('AMK_B_L4_C6')
        assert c.id == 19

    def test_get_building_by_id(self):
        b = self.osm_bridge.get_building(149)
        assert b.geometry is not None
        assert b.id == 149
        assert b.stairs is None
        assert b.elevators is not None
        assert b.floors is not None

    def test_get_building_by_name(self):
        b = self.osm_bridge.get_building('AMK')
        assert b.geometry is not None
        assert b.id == 149
        assert b.stairs is None
        assert b.elevators is not None
        assert b.floors is not None

    def test_search_by_scope_for_building(self):
        b = self.osm_bridge.get_building('AMK')
        f = b.floor('AMK_L4')
        assert f.id == 164

        e = b.elevator('AMK_B_E1')
        assert e.id == 5

        self.assertRaises(Exception, b.stair, 'AMK_B_S1')
Esempio n. 13
0
 def setUp(self):
     self.osm_bridge = OSMBridge()
Esempio n. 14
0
class TestLocalAreaFinder(unittest.TestCase):
    '''
    Unit tests for local area finder class 
    '''
    def setUp(self):
        self.osm_bridge = OSMBridge()

    def test_given_area_name_inside_la_with_xy(self):
        """TODO: Docstring for test_given_area_name_inside_la_with_xy.

        """
        area_name = "AMK_B_L-1_C29"
        expected_local_area_ref = "AMK_B_L-1_C29_LA1"
        x = 14.054641069320496
        y = -20.23611060809344
        local_area = self.osm_bridge.get_local_area(x=x,
                                                    y=y,
                                                    area_name=area_name,
                                                    isLatlong=False)
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_given_area_name_outside_la_with_xy(self):
        """TODO: Docstring for test_given_area_name_outside_la_with_xy.

        """
        area_name = "AMK_B_L-1_C29"
        expected_local_area_ref = "AMK_B_L-1_C29_LA1"
        x = 13.190239037096035
        y = -20.165316094644368
        local_area = self.osm_bridge.get_local_area(x=x,
                                                    y=y,
                                                    area_name=area_name,
                                                    isLatlong=False)
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_given_area_name_inside_la_with_latlong(self):
        """TODO: Docstring for test_given_area_name_inside_la_with_xy.

        """
        area_name = "AMK_B_L-1_C29"
        expected_local_area_ref = "AMK_B_L-1_C29_LA1"
        latitude = 50.1361671
        longitude = 8.6476004
        local_area = self.osm_bridge.get_local_area(x=latitude,
                                                    y=longitude,
                                                    area_name=area_name,
                                                    isLatlong=True)
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_given_area_name_outside_la_with_latlong(self):
        """TODO: Docstring for test_given_area_name_outside_la_with_xy.

        """
        area_name = "AMK_B_L-1_C29"
        expected_local_area_ref = "AMK_B_L-1_C29_LA1"
        latitude = 50.1361677
        longitude = 8.6475883
        local_area = self.osm_bridge.get_local_area(x=latitude,
                                                    y=longitude,
                                                    area_name=area_name,
                                                    isLatlong=True)
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_not_given_area_name(self):
        """TODO: Docstring for test_not_given_area_name.

        """
        expected_local_area_ref = "AMK_B_L-1_C29_LA1"
        latitude = 50.1361677
        longitude = 8.6475883
        local_area = self.osm_bridge.get_local_area(x=latitude,
                                                    y=longitude,
                                                    isLatlong=True,
                                                    floor_name="AMK_L-1")
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_not_given_area_name_edge_case(self):
        """TODO: Docstring for test_not_given_area_name.
        Here, the position given is such that, the nearest topology node is actually another area

        """
        expected_local_area_ref = "AMK_B_L-1_C23_LA2"
        latitude = 50.1363136
        longitude = 8.6475123
        local_area = self.osm_bridge.get_local_area(x=latitude,
                                                    y=longitude,
                                                    isLatlong=True,
                                                    floor_name="AMK_L-1")
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_given_area_name_with_behaviour(self):
        """TODO: Docstring for test_given_area_name_with_behaviour.
        :returns: TODO

        """
        area_name = "AMK_D_L-1_C41"
        expected_local_area_ref = "AMK_D_L-1_C41_LA2"
        local_area = self.osm_bridge.get_local_area(area_name=area_name,
                                                    behaviour="docking")
        self.assertEqual(local_area.ref, expected_local_area_ref)

        area_name = "AMK_A_L-1_RoomBU21"
        expected_local_area_ref = "AMK_A_L-1_RoomBU21_LA1"
        local_area = self.osm_bridge.get_local_area(area_name=area_name,
                                                    behaviour="undocking")
        self.assertEqual(local_area.ref, expected_local_area_ref)

    def test_not_given_area_name_with_behaviour(self):
        """This test takes more than 10 seconds to run, as it uses a brute force approach
        :returns: TODO

        """
        floor_name = "AMK_L-1"
        expected_local_area_ref = "AMK_D_L-1_C41_LA2"
        local_area = self.osm_bridge.get_local_area(floor_name=floor_name,
                                                    behaviour="docking")
        self.assertEqual(local_area.ref, expected_local_area_ref)

        floor_name = "AMK_L-1"
        expected_local_area_ref = "AMK_A_L-1_RoomBU21_LA1"
        local_area = self.osm_bridge.get_local_area(floor_name=floor_name,
                                                    behaviour="undocking")
        self.assertEqual(local_area.ref, expected_local_area_ref)
 def __init__(self, lat, lon, building, floor):
     self.osm_bridge = OSMBridge(
         global_origin=[REF_LATITUDE, REF_LONGITUDE])
     self.floor = self.osm_bridge.get_floor(building + '_L' + str(floor))
 def setUp(self):
     self.osm_bridge = OSMBridge(server_ip='172.16.1.101', server_port=8000, global_origin=[
                                 50.7800401, 7.18226], coordinate_system='cartesian')
     self.compute_orientation = ComputeOrientation()