opendrive格式完全解析
在carla仿真环境中提供了很多的示例的xodr文件,如图所示
在目录: carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive
下面
有如下的xodr文件
OpenDriveMap.xodr Town01.xodr Town02.xodr Town03.xodr Town04.xodr Town05.xodr Town06.xodr Town07.xodr Town10HD.xodr
Town01_Opt.xodr Town02_Opt.xodr Town03_Opt.xodr Town04_Opt.xodr Town05_Opt.xodr Town06_Opt.xodr Town07_Opt.xodr Town10HD_Opt.xodr
下面就详细 看一下这里面到底有什么,也便于后面生成xodr做准备.
准备工作
都知道 xodr是用xml来写的,但是xml 是个树状结构,看上去比较麻烦,这里我用的是json进行解析的,因此用到一个包 xmltodict
使用python3的话,可以在ubuntu上直接用
sudo apt install python3-xmltodict
进行安装.
然后可以通过这种方式来把xodr转成dict类型的
读文件并转成dict
启动ipython3
In [1]: import xmltodict
In [2]: data = xmltodict.parse(open("./Town01.xodr").read())
In [3]:
In [3]: type(data)
Out[3]: collections.OrderedDict
In [4]: data.keys()
Out[4]: odict_keys(['OpenDRIVE'])
In [5]: opendrive = data["OpenDRIVE"]
In [6]: type(opendrive)
Out[6]: collections.OrderedDict
In [7]: opendrive.keys()
Out[7]: odict_keys(['header', 'road', 'controller', 'junction'])
In [8]: o_header = opendrive["header"]
In [9]: o_header
Out[9]:
OrderedDict([('@revMajor', '1'),
('@revMinor', '4'),
('@name', ''),
('@version', '1'),
('@date', '2020-07-29T12:17:19'),
('@north', '2.8349990637833574e+1'),
('@south', '-3.5690998535156251e+2'),
('@east', '4.2268105762411665e+2'),
('@west', '-2.8359911988457576e+1'),
('@vendor', 'VectorZero'),
('geoReference',
'+proj=tmerc +lat_0=0 +lon_0=0 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs'),
('userData',
OrderedDict([('vectorScene',
OrderedDict([('@program', 'RoadRunner'),
('@version',
'2019.2.12 (build 5161c1572)')]))]))])
会发现 header里面存储的是一些基本的信息.
road
继续探索road
.
In [10]: o_read = opendrive["road"]
In [11]: type(o_read)
Out[11]: list
In [12]: o_read1 = o_read[0]
In [13]: type(o_read1)
Out[13]: collections.OrderedDict
In [14]: o_read1.keys()
Out[14]: odict_keys(['@name', '@length', '@id', '@junction', 'link', 'type', 'planView', 'elevationProfile', 'lateralProfile', 'lanes', 'objects', 'signals'])
In [16]: o_read1["@name"]
Out[16]: 'Road 0'
In [18]: o_read1["@length"]
Out[18]: '3.6360000000000007e+1'
In [19]: o_read1["@id"]
Out[19]: '0'
In [20]: o_read1["@junction"]
Out[20]: '-1'
In [22]: o_read1["link"]
Out[22]:
OrderedDict([('predecessor',
OrderedDict([('@elementType', 'road'),
('@elementId', '11'),
('@contactPoint', 'start')])),
('successor',
OrderedDict([('@elementType', 'junction'),
('@elementId', '26')]))])
In [23]: o_read1["type"]
Out[23]:
OrderedDict([('@s', '0.0000000000000000e+0'),
('@type', 'town'),
('speed', OrderedDict([('@max', '25'), ('@unit', 'mph')]))])
In [24]: o_read1["planView"]
Out[24]:
OrderedDict([('geometry',
OrderedDict([('@s', '0.0000000000000000e+0'),
('@x', '3.8458999633789063e+2'),
('@y', '-1.9999999552965164e-2'),
('@hdg', '3.1410614169049995e+0'),
('@length', '3.6360000000000007e+1'),
('line', None)]))])
In [25]: o_read1["elevationProfile"]
Out[25]:
OrderedDict([('elevation',
OrderedDict([('@s', '0.0000000000000000e+0'),
('@a', '0.0000000000000000e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')]))])
In [27]: o_read1["lateralProfile"]
Out[27]:
OrderedDict([('superelevation',
OrderedDict([('@s', '0.0000000000000000e+0'),
('@a', '0.0000000000000000e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')]))])
road:lanes
看一下每一条road的lanes
In [38]: o_read1.keys()
Out[38]: odict_keys(['@name', '@length', '@id', '@junction', 'link', 'type', 'planView', 'elevationProfile', 'lateralProfile', 'lanes', 'objects', 'signals'])
In [39]: lanes1 = o_read1["lanes"]
In [40]: lanes1.keys()
Out[40]: odict_keys(['laneOffset', 'laneSection'])
In [41]: lanes1["laneOffset"]
Out[41]:
OrderedDict([('@s', '0.0000000000000000e+0'),
('@a', '0.0000000000000000e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])
In [42]: lanes1["laneSection"].keys()
Out[42]: odict_keys(['@s', 'left', 'center', 'right'])
In [44]: lanes1["laneSection"]["left"]
Out[44]:
OrderedDict([('lane',
[OrderedDict([('@id', '3'),
('@type', 'sidewalk'),
('@level', 'false'),
('link',
OrderedDict([('predecessor',
OrderedDict([('@id', '-3')]))])),
('width',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@a', '4.0000000000000009e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])),
('roadMark',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@type', 'none'),
('@material', 'standard'),
('@color', 'white'),
('@laneChange', 'none')])),
('userData',
OrderedDict([('vectorLane',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@laneId',
'{c5563b95-8ec9-4e36-a1f4-1f0366f5ad74}'),
('@travelDir',
'undirected')]))]))]),
OrderedDict([('@id', '2'),
('@type', 'shoulder'),
('@level', 'false'),
('link',
OrderedDict([('predecessor',
OrderedDict([('@id', '-2')]))])),
('width',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@a', '2.9999999999999982e-1'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])),
('roadMark',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@type', 'curb'),
('@material', 'standard'),
('@width', '1.5239999999999998e-1'),
('@laneChange', 'none')])),
('userData',
OrderedDict([('vectorLane',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@laneId',
'{a029c15c-ebff-48c6-853c-c4c473510068}'),
('@travelDir',
'undirected')]))]))]),
OrderedDict([('@id', '1'),
('@type', 'driving'),
('@level', 'false'),
('link',
OrderedDict([('predecessor',
OrderedDict([('@id', '-1')]))])),
('width',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@a', '4.0000000000000000e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])),
('roadMark',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@type', 'none'),
('@material', 'standard'),
('@color', 'white'),
('@laneChange', 'none')])),
('userData',
OrderedDict([('vectorLane',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@laneId',
'{408913da-91fa-4211-83b1-cdbc8eceb9e8}'),
('@travelDir',
'backward')]))]))])])])
In [46]: lanes1["laneSection"]["right"]
Out[46]:
OrderedDict([('lane',
[OrderedDict([('@id', '-1'),
('@type', 'driving'),
('@level', 'false'),
('link',
OrderedDict([('predecessor',
OrderedDict([('@id', '1')]))])),
('width',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@a', '4.0000000000000000e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])),
('roadMark',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@type', 'none'),
('@material', 'standard'),
('@color', 'white'),
('@laneChange', 'none')])),
('userData',
OrderedDict([('vectorLane',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@laneId',
'{7487e32f-7117-4384-a240-4169022e6340}'),
('@travelDir',
'forward')]))]))]),
OrderedDict([('@id', '-2'),
('@type', 'shoulder'),
('@level', 'false'),
('link',
OrderedDict([('predecessor',
OrderedDict([('@id', '2')]))])),
('width',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@a', '2.9999999999999982e-1'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])),
('roadMark',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@type', 'curb'),
('@material', 'standard'),
('@width', '1.5239999999999998e-1'),
('@laneChange', 'none')])),
('userData',
OrderedDict([('vectorLane',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@laneId',
'{e944bf6a-ea69-40a4-b4fd-0d9cdf40b613}'),
('@travelDir',
'undirected')]))]))]),
OrderedDict([('@id', '-3'),
('@type', 'sidewalk'),
('@level', 'false'),
('link',
OrderedDict([('predecessor',
OrderedDict([('@id', '3')]))])),
('width',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@a', '4.0000000000000009e+0'),
('@b', '0.0000000000000000e+0'),
('@c', '0.0000000000000000e+0'),
('@d', '0.0000000000000000e+0')])),
('roadMark',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@type', 'none'),
('@material', 'standard'),
('@color', 'white'),
('@laneChange', 'none')])),
('userData',
OrderedDict([('vectorLane',
OrderedDict([('@sOffset',
'0.0000000000000000e+0'),
('@laneId',
'{303aa2f9-929e-43d1-935d-c181d3456f6f}'),
('@travelDir',
'undirected')]))]))])])])
In [47]: lanes1["laneSection"]["center"]
Out[47]:
OrderedDict([('lane',
OrderedDict([('@id', '0'),
('@type', 'none'),
('@level', 'false'),
('roadMark',
OrderedDict([('@sOffset', '0.0000000000000000e+0'),
('@type', 'broken'),
('@material', 'standard'),
('@color', 'yellow'),
('@width', '1.2500000000000000e-1'),
('@laneChange', 'none')])),
('userData', None)]))])
所以每条road的lanes里面有自己的信息,也有它的左,右两边的lane的信息
road:objects
看一下road[“objects”] 是什么
In [48]: o_read1.keys()
Out[48]: odict_keys(['@name', '@length', '@id', '@junction', 'link', 'type', 'planView', 'elevationProfile', 'lateralProfile', 'lanes', 'objects', 'signals'])
In [49]: objects1 = o_read1["objects"]
In [51]: type(objects1)
Out[51]: collections.OrderedDict
In [52]: objects1.keys()
Out[52]: odict_keys(['object'])
In [53]: obj = objects1["object"]
In [54]: type(obj)
Out[54]: collections.OrderedDict
In [55]: obj.keys()
Out[55]: odict_keys(['@id', '@name', '@s', '@t', '@zOffset', '@hdg', '@roll', '@pitch', '@orientation', '@type', '@height', '@width', '@length'])
In [56]: obj
Out[56]:
OrderedDict([('@id', '435'),
('@name', 'Speed_30'),
('@s', '1.7472293596265814e+1'),
('@t', '-4.3197185908605400e+0'),
('@zOffset', '1.5096607804298401e-1'),
('@hdg', '5.3128035506233573e-4'),
('@roll', '0.0000000000000000e+0'),
('@pitch', '0.0000000000000000e+0'),
('@orientation', '-'),
('@type', '-1'),
('@height', '0.0000000000000000e+0'),
('@width', '0.0000000000000000e+0'),
('@length', '0.0000000000000000e+0')])
上面这个估计是一个限速标志, 根据名字 Speed_30 猜测的.
road:signals
标志
In [57]: o_read1.keys()
Out[57]: odict_keys(['@name', '@length', '@id', '@junction', 'link', 'type', 'planView', 'elevationProfile', 'lateralProfile', 'lanes', 'objects', 'signals'])
In [58]: sigs = o_read1["signals"]
In [59]: type(sigs)
Out[59]: collections.OrderedDict
In [60]: sigs.keys()
Out[60]: odict_keys(['signal'])
In [61]: sigs
Out[61]:
OrderedDict([('signal',
OrderedDict([('@name', 'Signal_3Light_Post01'),
('@id', '362'),
('@s', '3.5840466582261428e+1'),
('@t', '-4.4797897637266599e+0'),
('@zOffset', '-6.9904327392578125e-1'),
('@hOffset', '-3.5448458390874293e-8'),
('@roll', '0.0000000000000000e+0'),
('@pitch', '0.0000000000000000e+0'),
('@orientation', '-'),
('@dynamic', 'yes'),
('@country', 'OpenDRIVE'),
('@type', '1000001'),
('@subtype', '-1'),
('@value', '-1.0000000000000000e+0'),
('@text', ''),
('@height', '1.1595988571643829e+0'),
('@width', '5.2492320205637566e-1'),
('validity',
OrderedDict([('@fromLane', '0'),
('@toLane', '0')])),
('userData',
OrderedDict([('vectorSignal',
OrderedDict([('@signalId',
'{630a1ee4-4a24-4263-aaf7-df023be1ff6e}')]))]))]))])
这个估计是一个信号灯(红绿灯)
问题: opendrive中objects包括什么,signals包括什么?
controller
从其他地方查到,controller指的是红绿灯的控制器,这里面controller可以指定signal的id,意味着它可以控制的红绿灯的id,而且它可以指定多个,从而实现对多个红绿灯的同步控制。
In [62]: opendrive.keys()
Out[62]: odict_keys(['header', 'road', 'controller', 'junction'])
In [63]: contr = opendrive["controller"]
In [64]: type(contr)
Out[64]: list
In [65]: len(contr)
Out[65]: 36
In [66]: contr1 = contr[0]
In [67]: type(contr1)
Out[67]: collections.OrderedDict
In [68]: contr1.keys()
Out[68]: odict_keys(['@name', '@id', '@sequence', 'control'])
In [70]: contr1["@name"]
Out[70]: 'ctrl396'
In [71]: contr1["@id"]
Out[71]: '396'
In [72]: contr1["@sequence"]
Out[72]: '0'
In [73]: contr1["control"]
Out[73]:
[OrderedDict([('@signalId', '361'), ('@type', '')]),
OrderedDict([('@signalId', '361'), ('@type', '')])]
junction
In [75]: juns = opendrive["junction"]
In [76]: type(juns)
Out[76]: list
In [77]: jun1 = juns[0]
In [78]: type(jun1)
Out[78]: collections.OrderedDict
In [79]: jun1.keys()
Out[79]: odict_keys(['@id', '@name', 'connection', 'controller', 'userData'])
In [80]: jun1
Out[80]:
OrderedDict([('@id', '26'),
('@name', 'junction26'),
('connection',
[OrderedDict([('@id', '0'),
('@incomingRoad', '1'),
('@connectingRoad', '27'),
('@contactPoint', 'end'),
('laneLink',
OrderedDict([('@from', '1'), ('@to', '1')]))]),
OrderedDict([('@id', '1'),
('@incomingRoad', '1'),
('@connectingRoad', '28'),
('@contactPoint', 'start'),
('laneLink',
[OrderedDict([('@from', '2'), ('@to', '2')]),
OrderedDict([('@from', '3'), ('@to', '1')])])]),
OrderedDict([('@id', '2'),
('@incomingRoad', '16'),
('@connectingRoad', '33'),
('@contactPoint', 'end'),
('laneLink',
OrderedDict([('@from', '1'), ('@to', '1')]))]),
OrderedDict([('@id', '3'),
('@incomingRoad', '0'),
('@connectingRoad', '40'),
('@contactPoint', 'start'),
('laneLink',
[OrderedDict([('@from', '-1'), ('@to', '-1')]),
OrderedDict([('@from', '-2'), ('@to', '-2')]),
OrderedDict([('@from', '-3'),
('@to', '-3')])])]),
OrderedDict([('@id', '4'),
('@incomingRoad', '1'),
('@connectingRoad', '41'),
('@contactPoint', 'end'),
('laneLink',
OrderedDict([('@from', '1'), ('@to', '1')]))]),
OrderedDict([('@id', '5'),
('@incomingRoad', '0'),
('@connectingRoad', '46'),
('@contactPoint', 'start'),
('laneLink',
OrderedDict([('@from', '-1'), ('@to', '-1')]))]),
OrderedDict([('@id', '6'),
('@incomingRoad', '16'),
('@connectingRoad', '48'),
('@contactPoint', 'start'),
('laneLink',
[OrderedDict([('@from', '2'), ('@to', '2')]),
OrderedDict([('@from', '3'), ('@to', '1')])])]),
OrderedDict([('@id', '7'),
('@incomingRoad', '16'),
('@connectingRoad', '52'),
('@contactPoint', 'end'),
('laneLink',
OrderedDict([('@from', '1'), ('@to', '1')]))])]),
('controller',
[OrderedDict([('@id', '396'),
('@type', '0'),
('@sequence', '0')]),
OrderedDict([('@id', '397'),
('@type', '0'),
('@sequence', '1')]),
OrderedDict([('@id', '398'),
('@type', '0'),
('@sequence', '2')])]),
('userData',
OrderedDict([('vectorJunction',
OrderedDict([('@junctionId',
'{1bd52301-8d2c-42be-8b0b-2bae938cd581}')]))]))])
查看了calra 里面这些xodr文件里面,都是主要有 controller, header, junction,road
来组成的.
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town02.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town04_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town05.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town10HD_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town03.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town03_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town01_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town06_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/Town07_Opt.xodr
{'controller', 'header', 'junction', 'road'}
------------------------------
/data/carla-0.9.12/CarlaUE4/Content/Carla/Maps/OpenDrive/OpenDriveMap.xodr
{'controller', 'header', 'junction', 'road'}