test_lanelet2.py
Go to the documentation of this file.
1 import unittest
2 import lanelet2 # if we fail here, there is something wrong with registration
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
5 
6 
8  return AttributeMap({"key": "value"})
9 
10 
11 def getPoint():
12  return Point3d(getId(), 0, 0, 0, getAttributes())
13 
14 
16  return LineString3d(getId(), [getPoint(), getPoint()], getAttributes())
17 
18 
19 def getLanelet():
20  return Lanelet(getId(), getLineString(), getLineString(), getAttributes())
21 
22 
23 def getRegelem():
24  return TrafficLight(getId(), AttributeMap(), [getLineString()], getLineString())
25 
26 
28  lanelet = getLanelet()
29  lanelet.addRegulatoryElement(getRegelem())
30  return createMapFromLanelets([lanelet])
31 
32 
33 def checkPrimitiveId(testClass, primitive):
34  primitive.id = 30
35  testClass.assertEqual(primitive.id, 30)
36 
37 
38 def checkPrimitiveAttributes(testClass, primitive):
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)
46 
47 
48 class LaneletApiTestCase(unittest.TestCase):
49  def test_lanelet_id(self):
51 
54 
56  lanelet = getLanelet()
57  bound = getLineString()
58  lanelet.leftBound = bound
59  self.assertEqual(bound, lanelet.leftBound)
60 
62  regelem = getRegelem()
63  llt = getLanelet()
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)
68 
69 
70 class LaneletMapApiTestCase(unittest.TestCase):
72  map = getLaneletMap()
73  self.assertEqual(len(map.laneletLayer), 1)
74  self.assertEqual(len(map.regulatoryElementLayer), 1)
75 
77  map = getLaneletMap()
78  nearest = map.laneletLayer.nearest(BasicPoint2d(0, 0), 1)
79  self.assertEqual(len(nearest), 1)
80  self.assertTrue(map.laneletLayer.exists(nearest[0].id))
81 
82 
83 class GeometryApiTestCase(unittest.TestCase):
84  def test_distance_p2p(self):
85  self.assertEqual(distance(getPoint(), getPoint()), 0)
86 
88  self.assertEqual(distance(getPoint().basicPoint(), getPoint()), 0)
89 
90  def test_distance_l2l(self):
91  self.assertEqual(distance(getLineString(), getLineString()), 0)
92 
94  self.assertEqual(distance(getLanelet(), getLanelet()), 0)
95 
97  self.assertTrue(intersects2d(to2D(getLineString()), to2D(getLineString())))
98 
100  bbox = boundingBox2d(to2D(getLineString()))
101  self.assertEqual(bbox.min.x, 0)
102 
104  point_list = intersection(to2D(getLineString()), to2D(getLineString()))
105  self.assertEqual(point_list[0].x, 0.0)
106  self.assertEqual(point_list[0].y, 0.0)
107 
108 
109 if __name__ == '__main__':
110  unittest.main()
object to2D(object o)
Definition: geometry.cpp:88
def checkPrimitiveAttributes(testClass, primitive)
def getAttributes()
Definition: test_lanelet2.py:7
def checkPrimitiveId(testClass, primitive)
def getLineString()
def getLaneletMap()


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:59