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, RightOfWay, 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: unittest.TestCase, primitive: Lanelet):
34  primitive.id = 30
35  testClass.assertEqual(primitive.id, 30)
36 
37 
38 def checkPrimitiveAttributes(testClass: unittest.TestCase, primitive: Lanelet):
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  def test_lanelet_repr(self):
70  llt = getLanelet()
71  llt_from_repr = eval(repr(llt))
72  self.assertEqual(llt.id, llt_from_repr.id)
73  self.assertEqual(llt.leftBound.id, llt_from_repr.leftBound.id)
74  self.assertEqual(llt.rightBound.id, llt_from_repr.rightBound.id)
75  self.assertEqual(llt.attributes, llt_from_repr.attributes)
76 
78  llt = getLanelet()
79  llt2 = getLanelet()
80  regelem = RightOfWay(getId(), AttributeMap(), [llt], [llt2])
81  llt.addRegulatoryElement(regelem)
82  self.assertIn(f"Lanelet({llt.id}", repr(llt))
83  self.assertIn(f"RightOfWay({regelem.id},", repr(regelem))
84 
85 
86 class LaneletMapApiTestCase(unittest.TestCase):
88  map = getLaneletMap()
89  self.assertEqual(len(map.laneletLayer), 1)
90  self.assertEqual(len(map.regulatoryElementLayer), 1)
91 
93  map = getLaneletMap()
94  nearest = map.laneletLayer.nearest(BasicPoint2d(0, 0), 1)
95  self.assertEqual(len(nearest), 1)
96  self.assertTrue(map.laneletLayer.exists(nearest[0].id))
97 
98 
99 class GeometryApiTestCase(unittest.TestCase):
100  def test_distance_p2p(self):
101  self.assertEqual(distance(getPoint(), getPoint()), 0)
102 
104  self.assertEqual(distance(getPoint().basicPoint(), getPoint()), 0)
105 
106  def test_distance_l2l(self):
107  self.assertEqual(distance(getLineString(), getLineString()), 0)
108 
110  self.assertEqual(distance(getLanelet(), getLanelet()), 0)
111 
113  self.assertTrue(intersects2d(to2D(getLineString()), to2D(getLineString())))
114 
116  bbox = boundingBox2d(to2D(getLineString()))
117  self.assertEqual(bbox.min.x, 0)
118 
120  point_list = intersection(to2D(getLineString()), to2D(getLineString()))
121  self.assertEqual(point_list[0].x, 0.0)
122  self.assertEqual(point_list[0].y, 0.0)
123 
124 
125 if __name__ == '__main__':
126  unittest.main()
test_lanelet2.getLaneletMap
def getLaneletMap()
Definition: test_lanelet2.py:27
test_lanelet2.getLineString
def getLineString()
Definition: test_lanelet2.py:15
test_lanelet2.LaneletApiTestCase.test_lanelet_id
def test_lanelet_id(self)
Definition: test_lanelet2.py:49
test_lanelet2.LaneletApiTestCase.test_lanelet_repr_regelem_cycle
def test_lanelet_repr_regelem_cycle(self)
Definition: test_lanelet2.py:77
to2D
object to2D(object o)
Definition: geometry.cpp:89
test_lanelet2.GeometryApiTestCase.test_distance_basic_p2p
def test_distance_basic_p2p(self)
Definition: test_lanelet2.py:103
test_lanelet2.getLanelet
def getLanelet()
Definition: test_lanelet2.py:19
test_lanelet2.LaneletApiTestCase
Definition: test_lanelet2.py:48
test_lanelet2.LaneletApiTestCase.test_lanelet_repr
def test_lanelet_repr(self)
Definition: test_lanelet2.py:69
test_lanelet2.GeometryApiTestCase.test_intersects_l2l
def test_intersects_l2l(self)
Definition: test_lanelet2.py:112
test_lanelet2.getRegelem
def getRegelem()
Definition: test_lanelet2.py:23
test_lanelet2.LaneletMapApiTestCase.test_lanelet_map_basic
def test_lanelet_map_basic(self)
Definition: test_lanelet2.py:87
test_lanelet2.LaneletMapApiTestCase.test_lanelet_map_search
def test_lanelet_map_search(self)
Definition: test_lanelet2.py:92
test_lanelet2.GeometryApiTestCase.test_distance_l2l
def test_distance_l2l(self)
Definition: test_lanelet2.py:106
lanelet::python::repr
std::string repr(const boost::python::object &o)
Definition: repr.h:45
test_lanelet2.GeometryApiTestCase.test_distance_llt2llt
def test_distance_llt2llt(self)
Definition: test_lanelet2.py:109
test_lanelet2.getAttributes
def getAttributes()
Definition: test_lanelet2.py:7
test_lanelet2.checkPrimitiveAttributes
def checkPrimitiveAttributes(unittest.TestCase testClass, Lanelet primitive)
Definition: test_lanelet2.py:38
test_lanelet2.GeometryApiTestCase
Definition: test_lanelet2.py:99
test_lanelet2.LaneletMapApiTestCase
Definition: test_lanelet2.py:86
test_lanelet2.checkPrimitiveId
def checkPrimitiveId(unittest.TestCase testClass, Lanelet primitive)
Definition: test_lanelet2.py:33
test_lanelet2.GeometryApiTestCase.test_intersection_l2l
def test_intersection_l2l(self)
Definition: test_lanelet2.py:119
test_lanelet2.LaneletApiTestCase.test_lanelet_attributes
def test_lanelet_attributes(self)
Definition: test_lanelet2.py:52
test_lanelet2.getPoint
def getPoint()
Definition: test_lanelet2.py:11
test_lanelet2.LaneletApiTestCase.test_lanelet_modification
def test_lanelet_modification(self)
Definition: test_lanelet2.py:55
test_lanelet2.LaneletApiTestCase.test_lanelet_regelem
def test_lanelet_regelem(self)
Definition: test_lanelet2.py:61
test_lanelet2.GeometryApiTestCase.test_bounding_box_line
def test_bounding_box_line(self)
Definition: test_lanelet2.py:115
test_lanelet2.GeometryApiTestCase.test_distance_p2p
def test_distance_p2p(self)
Definition: test_lanelet2.py:100


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:14