def part2regulatory_elements(): # regulatory elements profit from pythons type system lanelet = get_a_lanelet() light = get_linestring_at_y(3) regelem = TrafficLight(getId(), AttributeMap(), [light]) lanelet.addRegulatoryElement(regelem) assert regelem in lanelet.regulatoryElements lights = [regelem for regelem in lanelet.regulatoryElements if isinstance(regelem, TrafficLight)] assert regelem in lights assert light in lights[0].trafficLights
def getAttributes(): return AttributeMap({"key": "value"})
def getRegelem(): return TrafficLight(getId(), AttributeMap(), [getLineString()], getLineString())
def get_test_map(): """ Map with this Layout: 3 ___ /5 / 2 _______/__/ | 2 | /4| 1 |_____|__/__| | 1 | 3 | 0 |_____|_____| 0 1 2 3 4 """ ll_1_right_start = Point3d(getId(), 0, 0) ll_1_left_start = Point3d(getId(), 0, 1) ll_1_right_end = Point3d(getId(), 2, 0) ll_1_left_end = Point3d(getId(), 2, 1) ll_2_left_start = Point3d(getId(), 0, 2) ll_2_left_end = Point3d(getId(), 2, 2) ll_3_right_end = Point3d(getId(), 4, 0) ll_3_left_end = Point3d(getId(), 4, 1) ll_4_left_end = Point3d(getId(), 4, 2) ll_5_left_end = Point3d(getId(), 3, 3) ll_5_right_end = Point3d(getId(), 4, 3) ls_attribute_map_dashed = AttributeMap({ 'subtype': 'dashed', 'type': 'line_thin' }) ll_1_right_bound = LineString3d(getId(), [ll_1_right_start, ll_1_right_end], ls_attribute_map_dashed) ll_1_left_bound = LineString3d(getId(), [ll_1_left_start, ll_1_left_end], ls_attribute_map_dashed) ll_2_left_bound = LineString3d(getId(), [ll_2_left_start, ll_2_left_end], ls_attribute_map_dashed) ll_3_right_bound = LineString3d(getId(), [ll_1_right_end, ll_3_right_end], ls_attribute_map_dashed) ll_3_left_bound = LineString3d(getId(), [ll_1_left_end, ll_3_left_end], ls_attribute_map_dashed) ll_4_left_bound = LineString3d(getId(), [ll_2_left_end, ll_4_left_end], ls_attribute_map_dashed) ll_5_left_bound = LineString3d(getId(), [ll_2_left_end, ll_5_left_end], ls_attribute_map_dashed) ll_5_right_bound = LineString3d(getId(), [ll_1_left_end, ll_5_right_end], ls_attribute_map_dashed) ll_attribute_map = AttributeMap({ 'location': 'urban', 'one_way': 'yes', 'region': 'de', 'subtype': 'road', 'type': 'lanelet' }) ll_1 = Lanelet(1, ll_1_left_bound, ll_1_right_bound, ll_attribute_map) ll_2 = Lanelet(2, ll_2_left_bound, ll_1_left_bound, ll_attribute_map) ll_3 = Lanelet(3, ll_3_left_bound, ll_3_right_bound, ll_attribute_map) ll_4 = Lanelet(4, ll_4_left_bound, ll_3_left_bound, ll_attribute_map) ll_5 = Lanelet(5, ll_5_left_bound, ll_5_right_bound, ll_attribute_map) lanelet_map = LaneletMap() lanelet_map.add(ll_1) lanelet_map.add(ll_2) lanelet_map.add(ll_3) lanelet_map.add(ll_4) lanelet_map.add(ll_5) return lanelet_map