def test_empty_point_set(self): # test WuPointSet iterator with empty list wupts = WuPointSet(GeographicMap().points) i = 0 for w in wupts: self.fail(msg='there are no points in this map') i += 1 self.assertEqual(i, 0) uu = 'da7c242f-2efe-5175-9961-49cc621b80b9' self.assertEqual(wupts.get(uu), None)
def test_empty_map_features(self): gm = GeoMap(GeographicMap()) self.assertEqual(gm.n_features, 0) # test GeoMapFeatures iterator with empty list gf = GeoMapFeatures(gm) i = 0 for f in gf: self.fail(msg='there are no features in this map') i += 1 self.assertEqual(i, 0) uu = 'da7c242f-2efe-5175-9961-49cc621b80b9' with self.assertRaises(KeyError): x = gf[uu]
def get_osm(url, bounds): """Get GeographicMap from Open Street Map XML data. The latitude and longitude bounding box returned may differ from the requested bounds. :param url: Uniform Resource Locator for map. :param bounds: Desired bounding box for map (presently ignored). :returns: GeographicMap message with header not filled in. """ # parse the URL filename = '' if url.startswith('file:///'): filename = url[7:] elif url.startswith('package://'): pkg_name, slash, pkg_path = url[10:].partition('/') pkg_dir = roslib.packages.get_pkg_dir(pkg_name) filename = pkg_dir + '/' + pkg_path else: raise ValueError('unsupported URL: ' + url) map = GeographicMap(id=geodesy.gen_uuid.makeUniqueID(url)) xm = None try: f = open(filename, 'r') xm = ElementTree.parse(f) except IOError: raise ValueError('unable to read ' + str(url)) except ElementTree.ParseError: raise ValueError('XML parse failed for ' + str(url)) osm = xm.getroot() # get map bounds for el in osm.iterfind('bounds'): map.bounds.min_latitude = float(get_required_attribute(el, 'minlat')) map.bounds.min_longitude = float(get_required_attribute(el, 'minlon')) map.bounds.max_latitude = float(get_required_attribute(el, 'maxlat')) map.bounds.max_longitude = float(get_required_attribute(el, 'maxlon')) # get map way-point nodes for el in osm.iterfind('node'): way = WayPoint() id = el.get('id') if id == None: raise ValueError('node id missing') way.id = makeOsmUniqueID('node', id) way.position.latitude = float(get_required_attribute(el, 'lat')) way.position.longitude = float(get_required_attribute(el, 'lon')) way.position.altitude = float(el.get('ele', float('nan'))) for tag_list in el.iterfind('tag'): kv = get_tag(tag_list) if kv != None: way.props.append(kv) map.points.append(way) # get map paths for el in osm.iterfind('way'): feature = MapFeature() id = el.get('id') if id == None: raise ValueError('way id missing') feature.id = makeOsmUniqueID('way', id) for nd in el.iterfind('nd'): way_id = get_required_attribute(nd, 'ref') feature.components.append(makeOsmUniqueID('node', way_id)) for tag_list in el.iterfind('tag'): kv = get_tag(tag_list) if kv != None: feature.props.append(kv) map.features.append(feature) # get relations for el in osm.iterfind('relation'): feature = MapFeature() id = el.get('id') if id == None: raise ValueError('relation id missing') feature.id = makeOsmUniqueID('relation', id) for mbr in el.iterfind('member'): mbr_type = get_required_attribute(mbr, 'type') if mbr_type in set(['node', 'way', 'relation']): mbr_id = get_required_attribute(mbr, 'ref') feature.components.append(makeOsmUniqueID(mbr_type, mbr_id)) else: print('unknown relation member type: ' + mbr_type) for tag_list in el.iterfind('tag'): kv = get_tag(tag_list) if kv != None: feature.props.append(kv) map.features.append(feature) return map
def get_osm(url, bounds): """Get `geographic_msgs/GeographicMap`_ from Open Street Map XML data. The latitude and longitude of the bounding box returned may differ from the requested bounds. :param url: Uniform Resource Locator for map. :param bounds: Desired `geographic_msgs/BoundingBox`_ for map (presently ignored). :returns: `geographic_msgs/GeographicMap`_ message (header not filled in). """ # parse the URL filename = '' if url.startswith('file:///'): filename = url[7:] elif url.startswith('package://'): pkg_name, slash, pkg_path = url[10:].partition('/') pkg_dir = roslib.packages.get_pkg_dir(pkg_name) filename = pkg_dir + '/' + pkg_path else: raise ValueError('unsupported URL: ' + url) gmap = GeographicMap(id = geodesy.gen_uuid.makeUniqueID(url)) xm = None try: f = open(filename, 'r') xm = ElementTree.parse(f) except IOError: raise ValueError('unable to read ' + str(url)) except ElementTree.ParseError: raise ValueError('XML parse failed for ' + str(url)) osm = xm.getroot() # get map bounds for el in osm.iterfind('bounds'): minlat = float(get_required_attribute(el, 'minlat')) minlon = float(get_required_attribute(el, 'minlon')) maxlat = float(get_required_attribute(el, 'maxlat')) maxlon = float(get_required_attribute(el, 'maxlon')) gmap.bounds = bounding_box.makeBounds2D(minlat, minlon, maxlat, maxlon) # get map way-point nodes for el in osm.iterfind('node'): way = WayPoint() el_id = el.get('id') if el_id is None: raise ValueError('node id missing') way.id = makeOsmUniqueID('node', el_id) way.position.latitude = float(get_required_attribute(el, 'lat')) way.position.longitude = float(get_required_attribute(el, 'lon')) way.position.altitude = float(el.get('ele', float('nan'))) for tag_list in el.iterfind('tag'): kv = get_tag(tag_list) if kv != None: way.props.append(kv) gmap.points.append(way) # get map paths for el in osm.iterfind('way'): feature = MapFeature() el_id = el.get('id') if el_id is None: raise ValueError('way id missing') feature.id = makeOsmUniqueID('way', el_id) for nd in el.iterfind('nd'): way_id = get_required_attribute(nd, 'ref') feature.components.append(makeOsmUniqueID('node', way_id)) for tag_list in el.iterfind('tag'): kv = get_tag(tag_list) if kv != None: feature.props.append(kv) gmap.features.append(feature) # get relations for el in osm.iterfind('relation'): feature = MapFeature() el_id = el.get('id') if el_id is None: raise ValueError('relation id missing') feature.id = makeOsmUniqueID('relation', el_id) for mbr in el.iterfind('member'): mbr_type = get_required_attribute(mbr, 'type') if mbr_type in set(['node', 'way', 'relation']): mbr_id = get_required_attribute(mbr, 'ref') feature.components.append(makeOsmUniqueID(mbr_type, mbr_id)) else: print('unknown relation member type: ' + mbr_type) for tag_list in el.iterfind('tag'): kv = get_tag(tag_list) if kv != None: feature.props.append(kv) gmap.features.append(feature) return gmap