3 from lanelet2.core
import AttributeMap, getId, BasicPoint2d, Point3d, LineString3d, Lanelet, RegulatoryElement, TrafficLight, LaneletMap, createMapFromLanelets
4 from lanelet2.geometry
import distance, intersects2d, boundingBox2d, to2D, intersection
8 return AttributeMap({
"key":
"value"})
30 return createMapFromLanelets([lanelet])
35 testClass.assertEqual(primitive.id, 30)
39 lenBefore = len(primitive.attributes)
40 primitive.attributes[
"newkey"] =
"newvalue" 41 testClass.assertEqual(lenBefore + 1, len(primitive.attributes))
42 testClass.assertTrue(
"newkey" in primitive.attributes)
43 testClass.assertEqual(primitive.attributes[
"newkey"],
"newvalue")
44 del primitive.attributes[
"newkey"]
45 testClass.assertFalse(
"newkey" in primitive.attributes)
58 lanelet.leftBound = bound
59 self.assertEqual(bound, lanelet.leftBound)
64 llt.addRegulatoryElement(regelem)
65 self.assertEqual(len(llt.trafficLights()), 1)
66 self.assertEqual(len(llt.trafficSigns()), 0)
67 self.assertEqual(len(llt.regulatoryElements), 1)
73 self.assertEqual(len(map.laneletLayer), 1)
74 self.assertEqual(len(map.regulatoryElementLayer), 1)
78 nearest = map.laneletLayer.nearest(BasicPoint2d(0, 0), 1)
79 self.assertEqual(len(nearest), 1)
80 self.assertTrue(map.laneletLayer.exists(nearest[0].id))
101 self.assertEqual(bbox.min.x, 0)
105 self.assertEqual(point_list[0].x, 0.0)
106 self.assertEqual(point_list[0].y, 0.0)
109 if __name__ ==
'__main__':
def test_lanelet_map_search(self)
def test_distance_p2p(self)
def test_intersection_l2l(self)
def test_lanelet_map_basic(self)
def test_lanelet_modification(self)
def checkPrimitiveAttributes(testClass, primitive)
def test_distance_l2l(self)
def test_intersects_l2l(self)
def checkPrimitiveId(testClass, primitive)
def test_lanelet_id(self)
def test_lanelet_regelem(self)
def test_distance_basic_p2p(self)
def test_bounding_box_line(self)
def test_lanelet_attributes(self)
def test_distance_llt2llt(self)