imap
imap copied to clipboard
ValueError: not enough values to unpack (expected 2, got 0)
@daohu527 , hi, could you please give me some comments about the issue. I can use the town.xord successfully. But when i using the t1.xord which i generated from roadrunner, i get he issue as shown below:
ll@ubuntu:~/Demo_Project/roadrunnerdemo/Exports$ imap -f -i ./t1.xodr -o ./test.txt
parse_geo_reference is +proj=tmerc +lat_0=31.5193375 +lon_0=120.4537025 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs :
Traceback (most recent call last):
File "/home/ll/.local/bin/imap", line 8, in
I think the issue may be caused by the incorrect t1.xord, but i didn't know the root cause.
Partial t1.xord information as shown below.
<?xml version="1.0" encoding="UTF-8"?>
<OpenDRIVE>
<header revMajor="1" revMinor="5" name="" version="1" date="2022-06-16T12:49:05" north="1.4032681214656503e+2" south="-1.1987680756892831e+2" east="3.1952362241611047e+2" west="-3.1970364560946985e+2" vendor="MathWorks">
<geoReference><![CDATA[+proj=tmerc +lat_0=31.5193375 +lon_0=120.4537025 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs ]]></geoReference>
<userData code="vectorScene">
<vectorScene program="RoadRunner" version="R2022a Update 2 (1.4.2.b34d038)"/>
</userData>
</header>
<road name="Road 0" length="1.5063469361350244e+1" id="0" junction="-1">
<link>
<predecessor elementType="road" elementId="3" contactPoint="end"/>
<successor elementType="road" elementId="8" contactPoint="start"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="-1.0790941405647732e+2" y="-3.2113340671356622e-1" hdg="1.8190900784009756e-3" length="3.7658636150472589e+0">
<line/>
</geometry>
<geometry s="3.7658636150472589e+0" x="-1.0414355667221673e+2" y="-3.1428296535294448e-1" hdg="1.8190900784009756e-3" length="7.4505805969238281e-6">
<arc curvature="-2.0000000000000000e-3"/>
</geometry>
<geometry s="3.7658710656278562e+0" x="-1.0414354922164847e+2" y="-3.1428295179967475e-1" hdg="1.8190900784009756e-3" length="7.5317272300945461e+0">
<line/>
</geometry>
<geometry s="1.1297598295722402e+1" x="-9.6611834453127273e+1" y="-3.0058206907843127e-1" hdg="1.8190900784009756e-3" length="7.4505805969238281e-6">
<arc curvature="2.0000000000000000e-3"/>
</geometry>
<geometry s="1.1297605746302999e+1" x="-9.6611827002559011e+1" y="-3.0058205552516154e-1" hdg="1.8190900784009756e-3" length="3.7658636150472447e+0">
<line/>
</geometry>
</planView>
<elevationProfile>
<elevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="2.5099999999999998e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="7.5299999999999994e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="1.2549999999999999e+1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</elevationProfile>
<lateralProfile>
<superelevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="1.5063469361350244e+1" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</lateralProfile>
<lanes>
<laneOffset s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<laneSection s="0.0000000000000000e+0" singleSide="false">
<center>
<lane id="0" type="none" level="false">
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="white" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="1.4959999999999999e+1" type="none" material="standard" color="white" laneChange="none"/>
<userData code="vectorLane"/>
</lane>
</center>
<userData code="vectorLaneSection">
<vectorLaneSection>
<carriageway rightBoundary="0" leftBoundary="0"/>
</vectorLaneSection>
</userData>
</laneSection>
</lanes>
</road>
<road name="Road 1" length="6.0247860905256072e+0" id="1" junction="-1">
<link>
<predecessor elementType="junction" elementId="10"/>
<successor elementType="road" elementId="4" contactPoint="start"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="-1.0039771100714995e+2" y="1.2742491412428981e+1" hdg="-1.5717046538185735e+0" length="6.0247860905256072e+0">
<line/>
</geometry>
</planView>
<elevationProfile>
<elevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="1.0058689849123992e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="3.0141310150876013e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="3.0158689849123990e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="5.0241310150876020e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</elevationProfile>
<lateralProfile>
<superelevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="6.0247860905256072e+0" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</lateralProfile>
<lanes>
<laneOffset s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<laneSection s="0.0000000000000000e+0" singleSide="false">
<center>
<lane id="0" type="none" level="false">
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="4.8500000000000005e+0" type="none" material="standard" color="white" laneChange="none"/>
<userData code="vectorLane"/>
</lane>
</center>
<userData code="vectorLaneSection">
<vectorLaneSection>
<carriageway rightBoundary="0" leftBoundary="0"/>
</vectorLaneSection>
</userData>
</laneSection>
</lanes>
</road>
<road name="Road 2" length="8.3979869246575987e+1" id="2" junction="-1">
<link>
<predecessor elementType="junction" elementId="10"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="-1.0042371882580767e+2" y="-1.5890160514739849e+1" hdg="-1.5717046538185753e+0" length="8.3979869246575987e+1">
<line/>
</geometry>
</planView>
<elevationProfile>
<elevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="7.2900000000000009e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="3.7289999999999999e+1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="3.8130000000000003e+1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="6.8129999999999995e+1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</elevationProfile>
<lateralProfile>
<superelevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-8.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-8.8360002574550123e-4" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="8.3979869246575987e+1" t="-8.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="8.3979869246575987e+1" t="-7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="8.3979869246575987e+1" t="-8.8360002574550123e-4" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="8.3979869246575987e+1" t="7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</lateralProfile>
<lanes>
<laneOffset s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<laneSection s="0.0000000000000000e+0" singleSide="false">
<left>
<lane id="3" type="shoulder" level="false">
<width sOffset="0.0000000000000000e+0" a="5.0000000000000000e-1" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="none" material="standard" color="white" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{a6e0875a-8897-4875-b9ae-58b63e91a905}" travelDir="backward"/>
</userData>
</lane>
<lane id="2" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="white" width="1.2500000000000000e-1" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{20c9dd5d-dd12-4e2a-a502-3df4da0fcb89}" travelDir="backward"/>
</userData>
</lane>
<lane id="1" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="7.2699999999999996e+0" type="broken" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="both"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{1a7866aa-ab91-45ef-85e4-7df99248e9e6}" travelDir="backward"/>
</userData>
</lane>
</left>
<center>
<lane id="0" type="none" level="false">
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="9.3800000000000008e+0" type="broken" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<userData code="vectorLane"/>
</lane>
</center>
<right>
<lane id="-1" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="7.2699999999999996e+0" type="broken" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="both"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{9f0a5321-10b2-489f-ac67-9838b7753691}" travelDir="forward"/>
</userData>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="white" width="1.2500000000000000e-1" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{e1c2522b-0104-4747-bda3-3b643915866b}" travelDir="forward"/>
</userData>
</lane>
<lane id="-3" type="shoulder" level="false">
<width sOffset="0.0000000000000000e+0" a="5.0000000000000000e-1" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="none" material="standard" color="white" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{c08287e9-5f6d-4063-bb42-ff3ef539b9d0}" travelDir="forward"/>
</userData>
</lane>
</right>
<userData code="vectorLaneSection">
<vectorLaneSection>
<carriageway rightBoundary="-3" leftBoundary="3"/>
</vectorLaneSection>
</userData>
</laneSection>
</lanes>
</road>
<road name="Road 3" length="5.0539752151325130e+0" id="3" junction="-1">
<link>
<predecessor elementType="junction" elementId="10"/>
<successor elementType="road" elementId="0" contactPoint="start"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="-1.1296338090958596e+2" y="-3.3032703781347161e-1" hdg="1.8190900784009756e-3" length="5.0539752151325130e+0">
<line/>
</geometry>
</planView>
<elevationProfile>
<elevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="8.3767079747791451e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="2.5223292025220854e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="2.5276707974779145e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="4.2123292025220858e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</elevationProfile>
<lateralProfile>
<superelevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="5.0539752151325130e+0" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</lateralProfile>
<lanes>
<laneOffset s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<laneSection s="0.0000000000000000e+0" singleSide="false">
<center>
<lane id="0" type="none" level="false">
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="3.7700000000000000e+0" type="none" material="standard" color="white" laneChange="none"/>
<userData code="vectorLane"/>
</lane>
</center>
<userData code="vectorLaneSection">
<vectorLaneSection>
<carriageway rightBoundary="0" leftBoundary="0"/>
</vectorLaneSection>
</userData>
</laneSection>
</lanes>
</road>
<road name="Road 4" length="1.4052369480349761e+1" id="4" junction="-1">
<link>
<predecessor elementType="road" elementId="1" contactPoint="end"/>
<successor elementType="road" elementId="9" contactPoint="start"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="-1.0040318348241534e+2" y="6.7177078073021299e+0" hdg="-1.5717046538185766e+0" length="1.4052369480349761e+1">
<line/>
</geometry>
</planView>
<elevationProfile>
<elevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="2.3379384199417066e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="7.0220615800582928e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="7.0279384199417052e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="1.1712061580058293e+1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</elevationProfile>
<lateralProfile>
<superelevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="1.4052369480349761e+1" t="-5.0000000000000000e-1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</lateralProfile>
<lanes>
<laneOffset s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<laneSection s="0.0000000000000000e+0" singleSide="false">
<center>
<lane id="0" type="none" level="false">
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="white" width="1.2500000000000000e-1" laneChange="none"/>
<userData code="vectorLane"/>
</lane>
</center>
<userData code="vectorLaneSection">
<vectorLaneSection>
<carriageway rightBoundary="0" leftBoundary="0"/>
</vectorLaneSection>
</userData>
</laneSection>
</lanes>
</road>
<road name="Road 5" length="3.8414523967993279e+2" id="5" junction="-1">
<link>
<predecessor elementType="junction" elementId="10"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="-8.4634624846722744e+1" y="-2.7879442188406967e-1" hdg="1.8190900784009756e-3" length="2.8229021756184881e+2">
<line/>
</geometry>
<geometry s="2.8229021756184881e+2" x="1.9765512565356846e+2" y="2.3471662890323308e-1" hdg="1.8190900784009756e-3" length="1.0536712169439966e-5">
<arc curvature="-2.0000000000000000e-3"/>
</geometry>
<geometry s="2.8229022809856099e+2" x="1.9765513619026319e+2" y="2.3471664807045109e-1" hdg="1.8190900784009756e-3" length="1.0185501158137180e+2">
<line/>
</geometry>
</planView>
<elevationProfile>
<elevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="9.7530000000000015e+1" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="1.2753000000000003e+2" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="2.3334000000000000e+2" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<elevation s="2.6334000000000003e+2" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</elevationProfile>
<lateralProfile>
<superelevation s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-8.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="-9.2427359655644636e-5" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="1.8724065725744987e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="0.0000000000000000e+0" t="7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="3.8414523967993279e+2" t="-8.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="3.8414523967993279e+2" t="-7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="3.8414523967993279e+2" t="-9.2427359655644636e-5" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="3.8414523967993279e+2" t="1.8724065725744987e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<shape s="3.8414523967993279e+2" t="7.5000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
</lateralProfile>
<lanes>
<laneOffset s="0.0000000000000000e+0" a="0.0000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<laneSection s="0.0000000000000000e+0" singleSide="false">
<left>
<lane id="3" type="shoulder" level="false">
<width sOffset="0.0000000000000000e+0" a="5.0000000000000000e-1" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="none" material="standard" color="white" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{e915d1bc-26be-4b58-bdfa-1e00f4638d0e}" travelDir="backward"/>
</userData>
</lane>
<lane id="2" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="white" width="1.2500000000000000e-1" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{b14f1c31-c1f3-4016-ba9e-77bd50dcb98c}" travelDir="backward"/>
</userData>
</lane>
<lane id="1" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="1.0430000000000000e+1" type="broken" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="both"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{1bb565aa-454b-40db-b9ba-b0c8fef7a39c}" travelDir="backward"/>
</userData>
</lane>
</left>
<center>
<lane id="0" type="none" level="false">
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="1.2350000000000001e+1" type="broken" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<userData code="vectorLane"/>
</lane>
</center>
<right>
<lane id="-1" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="none"/>
<roadMark sOffset="1.2350000000000001e+1" type="broken" material="standard" color="yellow" width="1.2500000000000000e-1" laneChange="both"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{33db1d20-5e82-459a-9ca3-32867f2e9696}" travelDir="forward"/>
</userData>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0.0000000000000000e+0" a="3.5000000000000000e+0" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="solid" material="standard" color="white" width="1.2500000000000000e-1" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{1bd00cb7-3ae8-41c2-ba0e-5172527521cb}" travelDir="forward"/>
</userData>
</lane>
<lane id="-3" type="shoulder" level="false">
<width sOffset="0.0000000000000000e+0" a="5.0000000000000000e-1" b="0.0000000000000000e+0" c="0.0000000000000000e+0" d="0.0000000000000000e+0"/>
<roadMark sOffset="0.0000000000000000e+0" type="none" material="standard" color="white" laneChange="none"/>
<speed sOffset="0.0000000000000000e+0" max="4.0000000000000000e+1" unit="mph"/>
<userData code="vectorLane">
<vectorLane sOffset="0.0000000000000000e+0" laneId="{17f1048c-a4d7-43eb-b7ec-cc885ebbbbb3}" travelDir="forward"/>
</userData>
</lane>
</right>
<userData code="vectorLaneSection">
<vectorLaneSection>
<carriageway rightBoundary="-3" leftBoundary="3"/>
</vectorLaneSection>
</userData>
</laneSection>
</lanes>
</road>
<junction id="10" name="junction10">
<connection id="0" incomingRoad="2" connectingRoad="11" contactPoint="end">
<laneLink from="2" to="1"/>
</connection>
<connection id="1" incomingRoad="2" connectingRoad="12" contactPoint="end">
<laneLink from="1" to="1"/>
</connection>
<connection id="2" incomingRoad="7" connectingRoad="13" contactPoint="start">
<laneLink from="-2" to="-1"/>
</connection>
<connection id="3" incomingRoad="7" connectingRoad="14" contactPoint="start">
<laneLink from="-1" to="-1"/>
</connection>
<connection id="4" incomingRoad="2" connectingRoad="15" contactPoint="end">
<laneLink from="1" to="1"/>
</connection>
<connection id="5" incomingRoad="6" connectingRoad="16" contactPoint="start">
<laneLink from="-2" to="-1"/>
</connection>
<connection id="6" incomingRoad="5" connectingRoad="17" contactPoint="end">
<laneLink from="1" to="1"/>
</connection>
<connection id="7" incomingRoad="2" connectingRoad="18" contactPoint="end">
<laneLink from="2" to="1"/>
</connection>
<connection id="8" incomingRoad="2" connectingRoad="20" contactPoint="end">
<laneLink from="3" to="3"/>
</connection>
<connection id="9" incomingRoad="7" connectingRoad="22" contactPoint="start">
<laneLink from="-2" to="-1"/>
</connection>
<connection id="10" incomingRoad="6" connectingRoad="23" contactPoint="start">
<laneLink from="-1" to="-1"/>
</connection>
<connection id="11" incomingRoad="5" connectingRoad="24" contactPoint="end">
<laneLink from="2" to="1"/>
</connection>
<connection id="12" incomingRoad="7" connectingRoad="25" contactPoint="start">
<laneLink from="-1" to="-1"/>
</connection>
<connection id="13" incomingRoad="7" connectingRoad="28" contactPoint="start">
<laneLink from="-3" to="-3"/>
</connection>
<connection id="14" incomingRoad="5" connectingRoad="29" contactPoint="end">
<laneLink from="2" to="1"/>
</connection>
<connection id="15" incomingRoad="6" connectingRoad="30" contactPoint="start">
<laneLink from="-1" to="-1"/>
</connection>
<connection id="16" incomingRoad="5" connectingRoad="31" contactPoint="end">
<laneLink from="1" to="1"/>
</connection>
<connection id="17" incomingRoad="6" connectingRoad="32" contactPoint="start">
<laneLink from="-2" to="-1"/>
</connection>
<connection id="18" incomingRoad="6" connectingRoad="35" contactPoint="start">
<laneLink from="-3" to="-3"/>
</connection>
<connection id="19" incomingRoad="5" connectingRoad="37" contactPoint="end">
<laneLink from="3" to="3"/>
</connection>
<userData code="vectorJunction">
<vectorJunction junctionId="{04560714-ab60-4ce2-ac33-3bdf65b1a8fe}"/>
</userData>
</junction>
</OpenDRIVE>
I will try and feedback soon!
This error is related to the junction, have you confirmed that the junction is normal?
In short, opendrive does not provide the shape of junction, so we have to generate it according to the road of the intersection, the problem may be here.
@daohu527 According to your comments, i found it seems be caused by the road 0, road 1 which have road information but no lanes information. road 0 and road 1 only have center lane (reference line) information. Is this the root cause ? After i delete all related information of these roads which have no lanes, it can convert successfully. By the way, i found the value of x and y is very small after i convert the opendiver map to apollo map by the commands. The value should be very big if we use +proj=utm. Am i missing anything ?
According to your comments, i found it seems be caused by the road 0, road 1 which have road information but no lanes information. road 0 and road 1 only have center lane (reference line) information. Is this the root cause ? After i delete all related information of these roads which have no lanes, it can convert successfully.
yes, we find first lane and last lane's start point in the road and connect them to form a straight line. you know the junction is composed of 4 roads, so we will get a rectangle, we get the shape of the junction by the above method. This may have something to do with the shape of the intersection. More complex scenarios need to be tested. If it is an 4 road intersection, I think there is no problem.
By the way, i found the value of x and y is very small after i convert the opendiver map to apollo map by the commands. The value should be very big if we use +proj=utm. Am i missing anything ?
+proj
will be the origin, so our map's coordinate will be (+proj + offset), At present, only the time zone cannot be automatically generated, but the proj is generated according to opendrive.
+proj
will be the origin, so our map's coordinate will be (+proj + offset), At present, only the time zone cannot be automatically generated, but the proj is generated according to opendrive.
@daohu527 as you mentioned the coordinate will be origin (+proj) + (+offset), so i think the origin location should be (+lat_0=31.5193375 +lon_0=120.4537025) in my xodr file. I think if we use +proj=utm to transfer the coordinates, the x, y would be a value near (x10e5 y10e6) not like below. Am i correct ? Or the below outputs is correct from this imap tool ?
header { version: "1" date: "2022-06-28T15:15:40" projection { proj: "+proj=utm +zone=51 +ellps=WGS84 +datum=WGS84 +units=m +no_defs" } rev_major: "1" rev_minor: "5" left: -319.70364560946985 top: 140.32681214656503 right: 319.52362241611047 bottom: -119.87680756892831 vendor: "MathWorks" } junction { id { id: "4" } polygon { point { x: -114.86826688872571 y: 7.166220208279006 z: 0.0 } point { x: -114.8409805525985 y: -7.833754973562488 z: 0.0 } point { x: -107.92371573184043 y: -15.883348062999039 z: 0.0 } point { x: -92.9237219197749 y: -15.896972966480659 z: 0.0 } point { x: -84.62098167865913 y: -7.778782012804816 z: 0.0 } point { x: -84.64826801478635 y: 7.2211931690366775 z: 0.0 } point { x: -92.896045942634 y: 14.572195964937421 z: 0.0 } point { x: -107.89603975469953 y: 14.585820868419074 z: 0.0 } } } lane { id { id: "road_0_lane_0_2" } central_curve { segment { line_segment { point { x: -95.25002045108182 y: -99.89489457852557 } point { x: -95.24911212418304 y: -98.89489499105453 } point { x: -95.24820379728428 y: -97.89489540358349 } point { x: -95.2472954703855 y: -96.89489581611245 } point { x: -95.24638714348673 y: -95.89489622864141 } point { x: -95.24547881658795 y: -94.89489664117038 } point { x: -95.24457048968917 y: -93.89489705369934 } point { x: -95.2436621627904 y: -92.8948974662283 } point { x: -95.24275383589162 y: -91.89489787875726 } point { x: -95.24184550899285 y: -90.89489829128622 } point { x: -95.24093718209407 y: -89.89489870381519 } point { x: -95.2400288551953 y: -88.89489911634415 } point { x: -95.23912052829652 y: -87.89489952887311 } point { x: -95.23821220139774 y: -86.89489994140207 } point { x: -95.23730387449898 y: -85.89490035393104 } point { x: -95.2363955476002 y: -84.89490076646 } point { x: -95.23548722070143 y: -83.89490117898896 } point { x: -95.23457889380265 y: -82.89490159151792 } point { x: -95.23367056690387 y: -81.89490200404688 } point { x: -95.2327622400051 y: -80.89490241657585 } point { x: -95.23185391310632 y: -79.89490282910482 } point { x: -95.23094558620755 y: -78.89490324163378 } point { x: -95.23003725930877 y: -77.89490365416275 } point { x: -95.22912893241 y: -76.89490406669171 } point { x: -95.22822060551123 y: -75.89490447922067 } point { x: -95.22731227861244 y: -74.89490489174963 } point { x: -95.22640395171368 y: -73.8949053042786 } point { x: -95.2254956248149 y: -72.89490571680756 } point { x: -95.22458729791613 y: -71.89490612933652 } point { x: -95.22367897101735 y: -70.89490654186548 } point { x: -95.22277064411857 y: -69.89490695439444 } point { x: -95.2218623172198 y: -68.8949073669234 } point { x: -95.22095399032102 y: -67.89490777945237 } point { x: -95.22004566342225 y: -66.89490819198133 } point { x: -95.21913733652347 y: -65.89490860451029 } point { x: -95.21822900962471 y: -64.89490901703925 } point { x: -95.21732068272593 y: -63.89490942956821 } point { x: -95.21641235582715 y: -62.89490984209717 } point { x: -95.21550402892838 y: -61.89491025462613 } point { x: -95.2145957020296 y: -60.894910667155095 } point { x: -95.21368737513083 y: -59.894911079684064 } point { x: -95.21277904823205 y: -58.894911492213026 } point { x: -95.21187072133327 y: -57.89491190474199 } point { x: -95.2109623944345 y: -56.89491231727095 } point { x: -95.21005406753572 y: -55.89491272979991 } point { x: -95.20914574063696 y: -54.894913142328875 } point { x: -95.20823741373817 y: -53.89491355485784 } point { x: -95.20732908683941 y: -52.8949139673868 } point { x: -95.20642075994063 y: -51.89491437991576 } point { x: -95.20551243304185 y: -50.89491479244472 } point { x: -95.20460410614308 y: -49.894915204973685 } point { x: -95.2036957792443 y: -48.89491561750265 } point { x: -95.20278745234553 y: -47.89491603003162 } point { x: -95.20187912544675 y: -46.89491644256058 } point { x: -95.20097079854797 y: -45.89491685508954 } point { x: -95.2000624716492 y: -44.8949172676185 } point { x: -95.19915414475042 y: -43.894917680147465 } point { x: -95.19824581785166 y: -42.89491809267643 } point { x: -95.19733749095288 y: -41.89491850520539 } point { x: -95.19642916405411 y: -40.89491891773435 } point { x: -95.19552083715533 y: -39.89491933026331 } point { x: -95.19461251025655 y: -38.894919742792275 } point { x: -95.19370418335778 y: -37.894920155321245 } point { x: -95.192795856459 y: -36.89492056785021 } point { x: -95.19188752956023 y: -35.89492098037917 } point { x: -95.19097920266145 y: -34.89492139290813 } point { x: -95.19007087576267 y: -33.89492180543709 } point { x: -95.1891625488639 y: -32.894922217966055 } point { x: -95.18825422196512 y: -31.894922630495014 } point { x: -95.18734589506636 y: -30.894923043023976 } point { x: -95.18643756816758 y: -29.894923455552938 } point { x: -95.18552924126881 y: -28.8949238680819 } point { x: -95.18462091437003 y: -27.894924280610862 } point { x: -95.18371258747125 y: -26.894924693139828 } point { x: -95.18280426057248 y: -25.89492510566879 } point { x: -95.1818959336737 y: -24.894925518197752 } point { x: -95.18098760677493 y: -23.894925930726714 } point { x: -95.18007927987615 y: -22.89492634325568 } point { x: -95.17917095297737 y: -21.894926755784642 } point { x: -95.1782626260786 y: -20.894927168313604 } point { x: -95.17735429917983 y: -19.894927580842566 } point { x: -95.17644597228106 y: -18.894927993371528 } point { x: -95.17553764538228 y: -17.89492840590049 } point { x: -95.17462931848351 y: -16.894928818429452 } point { x: -95.17372099158473 y: -15.894929230958416 } } s: 0.0 start_position { x: -95.25002045108182 y: -99.89489457852557 z: 0.0 } length: 83.97986924657599 } }
yes, imap for now is missing transforms! I need to check if apollo only supports utm and then feedback.
@Gabriel-Lv258 Although transforming the coordinates is possible, it is recommended to use the utm coordinate system.
I will add a command line to enter zoneid, and then implement the conversion of gps to utm coordinates.
@daohu527 Thank you for the update.
The opendrive header defined in 4.3. Overview of elements
link
porj cors can find here
so we need to transform cors to utm, use https://proj.org/operations/projections/tmerc.html as example, it will add an offset to all the x,y
fixed in #72