├── .gitignore ├── README.md └── VectorMap2Opendrive ├── BaseData.cs ├── CSVFileManager.cs ├── DataFile.cs ├── OpenDRIVE_1_4H.cs ├── OpenDrive.cs ├── OpenDrive ├── OpenDRIVE_1.4H.xsd └── output.xodr ├── Program.cs ├── Properties └── AssemblyInfo.cs ├── UnityEngine.dll ├── UnityEngine.dll.mdb ├── VM_DtLane.cs ├── VM_Lane.cs ├── VM_Node.cs ├── VM_Point.cs ├── VectorMap ├── dtlane.csv ├── lane.csv ├── node.csv └── point.csv ├── VectorMap2Opendrive.csproj ├── VectorMap2Opendrive.sln └── app.config /.gitignore: -------------------------------------------------------------------------------- 1 | /VectorMap2Opendrive/.vs/ 2 | /VectorMap2Opendrive/bin/ 3 | /VectorMap2Opendrive/obj/ 4 | 5 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # VectorMap2Opendrive 2 | Convert Autoware vector map to Opendrive format. 3 | 4 | This is a demo project about converting vector map to opendrive. So far it only supports 'dtlane', 'lane', 'point' and 'node' and uses 'Planeline' (Base on OpenDRIVE_1.4H.xsd) to generate opendrive. (Thus the opendrive file size is quite big.) 5 | 6 | #### **How to use it**: 7 | 1. Copy 'dtlane.csv' 'lane.csv' 'point.csv' and 'node.csv' into 'VectorMap' folder. 8 | 2. Open VectorMap2Opendrive.sln with VS2017. 9 | 3. Compile solution and run it, then new opendrive file will be generated and locate in 'OpenDrive' folder. 10 | 4. OpenDRIVE_1.4H.cs is auto-generated by xsd.exe based on OpenDRIVE_1.4H.xsd -------------------------------------------------------------------------------- /VectorMap2Opendrive/BaseData.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | 5 | 6 | namespace VectorMap2Opendrive 7 | { 8 | // Base Data 9 | public abstract class BaseData 10 | { 11 | public int m_ID; // the first line is always ID. 12 | public abstract void LoadData(int nRowIndex, DataFile file); 13 | } 14 | 15 | 16 | // Data Manager 17 | public abstract class BaseDataManager 18 | { 19 | protected Dictionary m_DataMap; 20 | protected int m_RowNum; 21 | 22 | public BaseDataManager() 23 | { 24 | m_DataMap = new Dictionary(64); 25 | } 26 | 27 | 28 | public void LoadData( string fileName, DataFile.LoadFile loadDelegate ) 29 | { 30 | DataFile datafile = new DataFile(); 31 | if ( datafile.LoadData(fileName, loadDelegate ) == false ) 32 | { 33 | StringBuilder sb = new StringBuilder(256); 34 | sb.AppendFormat("Loading File Error: {0}", fileName); 35 | throw new System.Exception(sb.ToString()); 36 | } 37 | 38 | m_RowNum = datafile.getRowNum(); 39 | 40 | for (int i = 0; i < m_RowNum; i++) 41 | { 42 | BaseData item = NewItem(); 43 | datafile.SeekTowList(i); 44 | try 45 | { 46 | item.LoadData(i, datafile); 47 | m_DataMap[item.m_ID] = item; 48 | } 49 | catch (System.Exception) 50 | { 51 | StringBuilder sb = new StringBuilder(256); 52 | sb.AppendFormat("Load {0} Error: row={1}", fileName, i); 53 | throw new System.Exception(sb.ToString()); 54 | } 55 | } 56 | 57 | _OnLoadComplete(); 58 | 59 | } 60 | 61 | protected virtual void _OnLoadComplete() 62 | { 63 | } 64 | 65 | protected abstract BaseData NewItem(); 66 | 67 | public virtual void DoDestroy() 68 | { 69 | 70 | } 71 | } 72 | } 73 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/CSVFileManager.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | 5 | namespace VectorMap2Opendrive 6 | { 7 | public class CSVFileManager : BaseDataManager where T : BaseData, new() 8 | { 9 | private static CSVFileManager s_Instance; 10 | 11 | public static CSVFileManager Instance() 12 | { 13 | if (s_Instance == null) 14 | 15 | s_Instance = new CSVFileManager(); 16 | 17 | return s_Instance; 18 | } 19 | 20 | 21 | 22 | protected override BaseData NewItem() 23 | { 24 | return new T(); 25 | } 26 | 27 | 28 | 29 | public T GetstItem(int nID) 30 | { 31 | 32 | if (m_DataMap.ContainsKey(nID)) 33 | 34 | return (T)m_DataMap[nID]; 35 | return null; 36 | } 37 | 38 | 39 | 40 | public int GetstItemCount() 41 | { 42 | return m_DataMap.Count; 43 | } 44 | 45 | 46 | 47 | public T GetstItemByIndex(int index, out int key) 48 | { 49 | int i = 0; 50 | foreach (KeyValuePair pair in m_DataMap) 51 | { 52 | if (i == index) 53 | { 54 | key = pair.Key; 55 | return (T)pair.Value; 56 | } 57 | i++; 58 | } 59 | // wrong index 60 | key = -1; 61 | return null; 62 | } 63 | 64 | 65 | public T GetstItemByID( int id ) 66 | { 67 | if ( m_DataMap.ContainsKey(id) ) 68 | { 69 | return (T)m_DataMap[id]; 70 | } 71 | 72 | return null; 73 | } 74 | 75 | 76 | 77 | public void Push(T item) 78 | { 79 | if (item != null) 80 | m_DataMap[item.m_ID] = item; 81 | } 82 | 83 | 84 | 85 | public void ClearUp() 86 | { 87 | s_Instance = null; 88 | } 89 | } 90 | } 91 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/DataFile.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Collections; 4 | using System.Text; 5 | 6 | namespace VectorMap2Opendrive 7 | { 8 | public class DataFile 9 | { 10 | public delegate string LoadFile(string fileName); 11 | 12 | ArrayList m_DataTypeArray; // first line, data type array 13 | ArrayList m_DataList; // all data 14 | ArrayList m_RowListNow; // current row 15 | 16 | 17 | public DataFile() 18 | { 19 | m_DataTypeArray = new ArrayList(16); 20 | m_DataList = new ArrayList(16); 21 | } 22 | 23 | 24 | // Load and parse data from string buffer 25 | public bool LoadData(string fileName, LoadFile loadDelegate ) 26 | { 27 | string text = loadDelegate(fileName); 28 | 29 | if (text == string.Empty || text == "") 30 | return false; 31 | 32 | text = text.Trim(); 33 | int index = 0; 34 | int line = 0; 35 | int end = 0; 36 | string tempstr = string.Empty; 37 | 38 | while (end > -1) 39 | { 40 | end = text.IndexOf("\r\n", index); 41 | if (end == -1) 42 | { 43 | tempstr = text.Substring(index, text.Length - index); 44 | } 45 | else 46 | { 47 | tempstr = text.Substring(index, end - index); 48 | } 49 | 50 | ParseStr(tempstr, line); 51 | line++; 52 | 53 | index = end + 1; 54 | } 55 | return true; 56 | } 57 | 58 | 59 | // Parse line content 60 | void ParseStr(string str, int line) 61 | { 62 | int index = 0; 63 | int end = 0; 64 | int dataNum = 0; 65 | 66 | if (line == 0) // load data type 67 | { 68 | while (end > -1) 69 | { 70 | end = str.IndexOf(",", index); 71 | string tempStr = string.Empty; 72 | if (end > -1) 73 | { 74 | tempStr = str.Substring(index, end - index); 75 | } 76 | else 77 | { 78 | tempStr = str.Substring(index, str.Length - index); 79 | } 80 | index = end + 1; 81 | 82 | m_DataTypeArray.Add(tempStr); 83 | } 84 | } 85 | else if (line > 0) // load table data, skip line 2, because line 2 are attributes' name and only for designer. 86 | { 87 | ArrayList mRowDataList = new ArrayList(16); 88 | m_DataList.Add(mRowDataList); 89 | dataNum = 0; 90 | while (dataNum < m_DataTypeArray.Count) 91 | { 92 | end = str.IndexOf(",", index); 93 | string tempStr = string.Empty; 94 | if (end > -1) 95 | { 96 | tempStr = str.Substring(index, end - index); 97 | } 98 | else 99 | { 100 | if (index < str.Length) 101 | { 102 | tempStr = str.Substring(index, str.Length - index); 103 | } 104 | else 105 | { 106 | tempStr = string.Empty; 107 | } 108 | end = str.Length - 1; 109 | } 110 | index = end + 1; 111 | 112 | dataNum++; 113 | 114 | mRowDataList.Add(tempStr); 115 | } 116 | } 117 | } 118 | 119 | 120 | public int getRowNum() 121 | { 122 | return m_DataList.Count; 123 | } 124 | 125 | 126 | public void SeekTowList( int col ) 127 | { 128 | if (col < m_DataList.Count) 129 | { 130 | m_RowListNow = (ArrayList)m_DataList[col]; 131 | } 132 | } 133 | 134 | 135 | 136 | public string getString(int col) 137 | { 138 | if (col >= m_DataTypeArray.Count) 139 | return null; 140 | 141 | return (string)m_RowListNow[col]; 142 | } 143 | } 144 | } 145 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/OpenDrive.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | using System.Xml.Serialization; 5 | using System.IO; 6 | 7 | namespace VectorMap2Opendrive 8 | { 9 | public class PolynomCurve 10 | { 11 | public double start; 12 | public double a, b, c, d; 13 | } 14 | 15 | public class ODLane 16 | { 17 | public int id; 18 | public string type; 19 | public string level; 20 | public string predecessor; 21 | public string successor; 22 | public List widths; 23 | } 24 | 25 | public class ODLaneSection 26 | { 27 | public double start; 28 | public ODLane center; 29 | public List lefts; 30 | public List rights; 31 | } 32 | 33 | public class PlaneLine 34 | { 35 | public double start; 36 | public double length; 37 | public double xs; 38 | public double ys; 39 | public double hdg; 40 | } 41 | 42 | public class ODRoad 43 | { 44 | public string name; 45 | public double length; 46 | public string id; 47 | public string junctionId; 48 | public string predecessor; 49 | public string successor; 50 | public List lineGeometries; 51 | public List elevations; 52 | public List laneSections; 53 | } 54 | 55 | 56 | public class OpenDrive 57 | { 58 | public List roads; 59 | 60 | public void SaveToXML(string path) 61 | { 62 | var data = new OpenDRIVE { }; 63 | 64 | data.header = new OpenDRIVEHeader(); 65 | data.header.revMajor = 1; 66 | data.header.revMajorSpecified = true; 67 | data.header.revMinor = 4; 68 | data.header.revMinorSpecified = true; 69 | 70 | data.road = new OpenDRIVERoad[roads.Count]; 71 | for (int i = 0; i < roads.Count; ++i ) 72 | { 73 | data.road[i] = new OpenDRIVERoad(); 74 | data.road[i].id = roads[i].id.ToString(); 75 | data.road[i].name = roads[i].name; 76 | data.road[i].length = roads[i].length; 77 | data.road[i].lengthSpecified = true; 78 | data.road[i].junction = roads[i].junctionId; 79 | data.road[i].link = new OpenDRIVERoadLink(); 80 | data.road[i].type = new OpenDRIVERoadType[1]; 81 | data.road[i].type[0] = new OpenDRIVERoadType(); 82 | data.road[i].type[0].s = 0; 83 | data.road[i].type[0].sSpecified = true; 84 | data.road[i].type[0].type = roadType.unknown; 85 | data.road[i].type[0].typeSpecified = true; 86 | 87 | // plan view 88 | int planCount = roads[i].lineGeometries.Count; 89 | data.road[i].planView = new OpenDRIVERoadGeometry[planCount]; 90 | for( int planIndex = 0; planIndex < planCount; ++planIndex ) 91 | { 92 | data.road[i].planView[planIndex] = new OpenDRIVERoadGeometry(); 93 | data.road[i].planView[planIndex].s = roads[i].lineGeometries[planIndex].start; 94 | data.road[i].planView[planIndex].sSpecified = true; 95 | data.road[i].planView[planIndex].x = roads[i].lineGeometries[planIndex].xs; 96 | data.road[i].planView[planIndex].xSpecified = true; 97 | data.road[i].planView[planIndex].y = roads[i].lineGeometries[planIndex].ys; 98 | data.road[i].planView[planIndex].ySpecified = true; 99 | data.road[i].planView[planIndex].hdg = roads[i].lineGeometries[planIndex].hdg; 100 | data.road[i].planView[planIndex].hdgSpecified = true; 101 | data.road[i].planView[planIndex].length = roads[i].lineGeometries[planIndex].length; 102 | data.road[i].planView[planIndex].lengthSpecified = true; 103 | data.road[i].planView[planIndex].Items = new OpenDRIVERoadGeometryLine[1]; 104 | data.road[i].planView[planIndex].Items[0] = new OpenDRIVERoadGeometryLine(); 105 | } 106 | 107 | // elevation 108 | int eleCount = roads[i].elevations.Count; 109 | data.road[i].elevationProfile = new OpenDRIVERoadElevationProfile(); 110 | data.road[i].elevationProfile.elevation = new OpenDRIVERoadElevationProfileElevation[eleCount]; 111 | for ( int eleIndex = 0; eleIndex < eleCount; ++eleIndex ) 112 | { 113 | data.road[i].elevationProfile.elevation[eleIndex] = new OpenDRIVERoadElevationProfileElevation(); 114 | data.road[i].elevationProfile.elevation[eleIndex].s = roads[i].elevations[eleIndex].start; 115 | data.road[i].elevationProfile.elevation[eleIndex].sSpecified = true; 116 | data.road[i].elevationProfile.elevation[eleIndex].a = roads[i].elevations[eleIndex].a; 117 | data.road[i].elevationProfile.elevation[eleIndex].aSpecified = true; 118 | data.road[i].elevationProfile.elevation[eleIndex].b = roads[i].elevations[eleIndex].b; 119 | data.road[i].elevationProfile.elevation[eleIndex].bSpecified = true; 120 | data.road[i].elevationProfile.elevation[eleIndex].c = roads[i].elevations[eleIndex].c; 121 | data.road[i].elevationProfile.elevation[eleIndex].cSpecified = true; 122 | data.road[i].elevationProfile.elevation[eleIndex].d = roads[i].elevations[eleIndex].d; 123 | data.road[i].elevationProfile.elevation[eleIndex].dSpecified = true; 124 | } 125 | 126 | 127 | // lane 128 | data.road[i].lanes = new OpenDRIVERoadLanes(); 129 | int laneCount = roads[i].laneSections.Count; 130 | data.road[i].lanes.laneSection = new OpenDRIVERoadLanesLaneSection[laneCount]; 131 | for ( int laneIndex = 0; laneIndex < laneCount; ++laneIndex) 132 | { 133 | data.road[i].lanes.laneSection[laneIndex] = new OpenDRIVERoadLanesLaneSection(); 134 | data.road[i].lanes.laneSection[laneIndex].s = roads[i].laneSections[laneIndex].start; 135 | data.road[i].lanes.laneSection[laneIndex].sSpecified = true; 136 | 137 | // center 138 | data.road[i].lanes.laneSection[laneIndex].center = new OpenDRIVERoadLanesLaneSectionCenter(); 139 | data.road[i].lanes.laneSection[laneIndex].center.lane = new centerLane(); 140 | data.road[i].lanes.laneSection[laneIndex].center.lane.id = roads[i].laneSections[laneIndex].center.id; 141 | data.road[i].lanes.laneSection[laneIndex].center.lane.idSpecified = true; 142 | data.road[i].lanes.laneSection[laneIndex].center.lane.type = laneType.none; 143 | data.road[i].lanes.laneSection[laneIndex].center.lane.typeSpecified = true; 144 | data.road[i].lanes.laneSection[laneIndex].center.lane.level = singleSide.@false; 145 | data.road[i].lanes.laneSection[laneIndex].center.lane.levelSpecified = true; 146 | data.road[i].lanes.laneSection[laneIndex].center.lane.link = new centerLaneLink(); 147 | data.road[i].lanes.laneSection[laneIndex].center.lane.link.predecessor = new centerLaneLinkPredecessor(); 148 | data.road[i].lanes.laneSection[laneIndex].center.lane.link.predecessor.id = -1; 149 | data.road[i].lanes.laneSection[laneIndex].center.lane.link.predecessor.idSpecified = true; 150 | 151 | // right 152 | data.road[i].lanes.laneSection[laneIndex].right = new OpenDRIVERoadLanesLaneSectionRight(); 153 | int rlaneCount = roads[i].laneSections[laneIndex].rights.Count; 154 | data.road[i].lanes.laneSection[laneIndex].right.lane = new lane[rlaneCount]; 155 | for( int rIndex = 0; rIndex < rlaneCount; ++ rIndex ) 156 | { 157 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex] = new lane(); 158 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].id = roads[i].laneSections[laneIndex].rights[rIndex].id; 159 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].idSpecified = true; 160 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].type = laneType.driving; 161 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].typeSpecified = true; 162 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].level = singleSide.@false; 163 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].levelSpecified = true; 164 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].link = new laneLink(); 165 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].link.predecessor = new laneLinkPredecessor(); 166 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].link.predecessor.id = -1; 167 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].link.predecessor.idSpecified = true; 168 | // width 169 | int widthCount = roads[i].laneSections[laneIndex].rights[rIndex].widths.Count; 170 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].Items = new laneWidth[widthCount]; 171 | for( int wIndex = 0; wIndex < widthCount; ++wIndex ) 172 | { 173 | laneWidth lw = new laneWidth(); 174 | lw.sOffset = roads[i].laneSections[laneIndex].rights[rIndex].widths[wIndex].start; 175 | lw.sOffsetSpecified = true; 176 | lw.a = roads[i].laneSections[laneIndex].rights[rIndex].widths[wIndex].a; 177 | lw.aSpecified = true; 178 | lw.b = roads[i].laneSections[laneIndex].rights[rIndex].widths[wIndex].b; 179 | lw.bSpecified = true; 180 | lw.c = roads[i].laneSections[laneIndex].rights[rIndex].widths[wIndex].c; 181 | lw.cSpecified = true; 182 | lw.d = roads[i].laneSections[laneIndex].rights[rIndex].widths[wIndex].d; 183 | lw.dSpecified = true; 184 | 185 | data.road[i].lanes.laneSection[laneIndex].right.lane[rIndex].Items[wIndex] = lw; 186 | } 187 | } 188 | } 189 | } 190 | 191 | var serializer = new XmlSerializer(typeof(OpenDRIVE)); 192 | 193 | using (var stream = new StreamWriter(path)) 194 | serializer.Serialize(stream, data); 195 | } 196 | } 197 | } 198 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/OpenDrive/OpenDRIVE_1.4H.xsd: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | XML Schema Definition for OpenDRIVE XML files - Rev. 1.4H, excluding SET records, (c)2015 by VIRES Simulationstechnologie GmbH, Germany 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | 233 | 234 | 235 | 236 | 237 | 238 | 239 | 240 | 241 | 242 | 243 | 244 | 245 | 246 | 247 | 248 | 249 | 250 | 251 | 252 | 253 | 254 | 255 | 256 | 257 | 258 | 259 | 260 | 261 | 262 | 263 | 264 | 265 | 266 | 267 | 268 | 269 | 270 | 271 | 272 | 273 | 274 | 275 | 276 | 277 | 278 | 279 | 280 | 281 | 282 | 283 | 284 | 285 | 286 | 287 | 288 | 289 | 290 | 291 | 292 | 293 | 294 | 295 | 296 | 297 | 298 | 299 | 300 | 301 | 302 | 303 | 304 | 305 | 306 | 307 | 308 | 309 | 310 | 311 | 312 | 313 | 314 | 315 | 316 | 317 | 318 | 319 | 320 | 321 | 322 | 323 | 324 | 325 | 326 | 327 | 328 | 329 | 330 | 331 | 332 | 333 | 334 | 335 | 336 | 337 | 338 | 339 | 340 | 341 | 342 | 343 | 344 | 345 | 346 | 347 | 348 | 349 | 350 | 351 | 352 | 353 | 354 | 355 | 356 | 357 | 358 | 359 | 360 | 361 | 362 | 363 | 364 | 365 | 366 | 367 | 368 | 369 | 370 | 371 | 372 | 373 | 374 | 375 | 376 | 377 | 378 | 379 | 380 | 381 | 382 | 383 | 384 | 385 | 386 | 387 | 388 | 389 | 390 | 391 | 392 | 393 | 394 | 395 | 396 | 397 | 398 | 399 | 400 | 401 | 402 | 403 | 404 | 405 | 406 | 407 | 408 | 409 | 410 | 411 | 412 | 413 | 414 | 415 | 416 | 417 | 418 | 419 | 420 | 421 | 422 | 423 | 424 | 425 | 426 | 427 | 428 | 429 | 430 | 431 | 432 | 433 | 434 | 435 | 436 | 437 | 438 | 439 | 440 | 441 | 442 | 443 | 444 | 445 | 446 | 447 | 448 | 449 | 450 | 451 | 452 | 453 | 454 | 455 | 456 | 457 | 458 | 459 | 460 | 461 | 462 | 463 | 464 | 465 | 466 | 467 | 468 | 469 | 470 | 471 | 472 | 473 | 474 | 475 | 476 | 477 | 478 | 479 | 480 | 481 | 482 | 483 | 484 | 485 | 486 | 487 | 488 | 489 | 490 | 491 | 492 | 493 | 494 | 495 | 496 | 497 | 498 | 499 | 500 | 501 | 502 | 503 | 504 | 505 | 506 | 507 | 508 | 509 | 510 | 511 | 512 | 513 | 514 | 515 | 516 | 517 | 518 | 519 | 520 | 521 | 522 | 523 | 524 | 525 | 526 | 527 | 528 | 529 | 530 | 531 | 532 | 533 | 534 | 535 | 536 | 537 | 538 | 539 | 540 | 541 | 542 | 543 | 544 | 545 | 546 | 547 | 548 | 549 | 550 | 551 | 552 | 553 | 554 | 555 | 556 | 557 | 558 | 559 | 560 | 561 | 562 | 563 | 564 | 565 | 566 | 567 | 568 | 569 | 570 | 571 | 572 | 573 | 574 | 575 | 576 | 577 | 578 | 579 | 580 | 581 | 582 | 583 | 584 | 585 | 586 | 587 | 588 | 589 | 590 | 591 | 592 | 593 | 594 | 595 | 596 | 597 | 598 | 599 | 600 | 601 | 602 | 603 | 604 | 605 | 606 | 607 | 608 | 609 | 610 | 611 | 612 | 613 | 614 | 615 | 616 | 617 | 618 | 619 | 620 | 621 | 622 | 623 | 624 | 625 | 626 | 627 | 628 | 629 | 630 | 631 | 632 | 633 | 634 | 635 | 636 | 637 | 638 | 639 | 640 | 641 | 642 | 643 | 644 | 645 | 646 | 647 | 648 | 649 | 650 | 651 | 652 | 653 | 654 | 655 | 656 | 657 | 658 | 659 | 660 | 661 | 662 | 663 | 664 | 665 | 666 | 667 | 668 | 669 | 670 | 671 | 672 | 673 | 674 | 675 | 676 | 677 | 678 | 679 | 680 | 681 | 682 | 683 | 684 | 685 | 686 | 687 | 688 | 689 | 690 | 691 | 692 | 693 | 694 | 695 | 696 | 697 | 698 | 699 | 700 | 701 | 702 | 703 | 704 | 705 | 706 | 707 | 708 | 709 | 710 | 711 | 712 | 713 | 714 | 715 | 716 | 717 | 718 | 719 | 720 | 721 | 722 | 723 | 724 | 725 | 726 | 727 | 728 | 729 | 730 | 731 | 732 | 733 | 734 | 735 | 736 | 737 | 738 | 739 | 740 | 741 | 742 | 743 | 744 | 745 | 746 | 747 | 748 | 749 | 750 | 751 | 752 | 753 | 754 | 755 | 756 | 757 | 758 | 759 | 760 | 761 | 762 | 763 | 764 | 765 | 766 | 767 | 768 | 769 | 770 | 771 | 772 | 773 | 774 | 775 | 776 | 777 | 778 | 779 | 780 | 781 | 782 | 783 | 784 | 785 | 786 | 787 | 788 | 789 | 790 | 791 | 792 | 793 | 794 | 795 | 796 | 797 | 798 | 799 | 800 | 801 | 802 | 803 | 804 | 805 | 806 | 807 | 808 | 809 | 810 | 811 | 812 | 813 | 814 | 815 | 816 | 817 | 818 | 819 | 820 | 821 | 822 | 823 | 824 | 825 | 826 | 827 | 828 | 829 | 830 | 831 | 832 | 833 | 834 | 835 | 836 | 837 | 838 | 839 | 840 | 841 | 842 | 843 | 844 | 845 | 846 | 847 | 848 | 849 | 850 | 851 | 852 | 853 | 854 | 855 | 856 | 857 | 858 | 859 | 860 | 861 | 862 | 863 | 864 | 865 | 866 | 867 | 868 | 869 | 870 | 871 | 872 | 873 | 874 | 875 | 876 | 877 | 878 | 879 | 880 | 881 | 882 | 883 | 884 | 885 | 886 | 887 | 888 | 889 | 890 | 891 | 892 | 893 | 894 | 895 | 896 | 897 | 898 | 899 | 900 | 901 | 902 | 903 | 904 | 905 | 906 | 907 | 908 | 909 | 910 | 911 | 912 | 913 | 914 | 915 | 916 | 917 | 918 | 919 | 920 | 921 | 922 | 923 | 924 | 925 | 926 | 927 | 928 | 929 | 930 | 931 | 932 | 933 | 934 | 935 | 936 | 937 | 938 | 939 | 940 | 941 | 942 | 943 | 944 | 945 | 946 | 947 | 948 | 949 | 950 | 951 | 952 | 953 | 954 | 955 | 956 | 957 | 958 | 959 | 960 | 961 | 962 | 963 | 964 | 965 | 966 | 967 | 968 | 969 | 970 | 971 | 972 | 973 | 974 | 975 | 976 | 977 | 978 | 979 | 980 | 981 | 982 | 983 | 984 | 985 | 986 | 987 | 988 | 989 | 990 | 991 | 992 | 993 | 994 | 995 | 996 | 997 | 998 | 999 | 1000 | 1001 | 1002 | 1003 | 1004 | 1005 | 1006 | 1007 | 1008 | 1009 | 1010 | 1011 | 1012 | 1013 | 1014 | 1015 | 1016 | 1017 | 1018 | 1019 | 1020 | 1021 | 1022 | 1023 | 1024 | 1025 | 1026 | 1027 | 1028 | 1029 | 1030 | 1031 | 1032 | 1033 | 1034 | 1035 | 1036 | 1037 | 1038 | 1039 | 1040 | 1041 | 1042 | 1043 | 1044 | 1045 | 1046 | 1047 | 1048 | 1049 | 1050 | 1051 | 1052 | 1053 | 1054 | 1055 | 1056 | 1057 | 1058 | 1059 | 1060 | 1061 | 1062 | 1063 | 1064 | 1065 | 1066 | 1067 | 1068 | 1069 | 1070 | 1071 | 1072 | 1073 | 1074 | 1075 | 1076 | 1077 | 1078 | 1079 | 1080 | 1081 | 1082 | 1083 | 1084 | 1085 | 1086 | 1087 | 1088 | 1089 | 1090 | 1091 | 1092 | 1093 | 1094 | 1095 | 1096 | 1097 | 1098 | 1099 | 1100 | 1101 | 1102 | 1103 | 1104 | 1105 | 1106 | 1107 | 1108 | 1109 | 1110 | 1111 | 1112 | 1113 | 1114 | 1115 | 1116 | 1117 | 1118 | 1119 | 1120 | 1121 | 1122 | 1123 | 1124 | 1125 | 1126 | 1127 | 1128 | 1129 | 1130 | 1131 | 1132 | 1133 | 1134 | 1135 | 1136 | 1137 | 1138 | 1139 | 1140 | 1141 | 1142 | 1143 | 1144 | 1145 | 1146 | 1147 | 1148 | 1149 | 1150 | 1151 | 1152 | 1153 | 1154 | 1155 | 1156 | 1157 | 1158 | 1159 | 1160 | 1161 | 1162 | 1163 | 1164 | 1165 | 1166 | 1167 | 1168 | 1169 | 1170 | 1171 | 1172 | 1173 | 1174 | 1175 | 1176 | 1177 | 1178 | 1179 | 1180 | 1181 | 1182 | 1183 | 1184 | 1185 | 1186 | 1187 | 1188 | 1189 | 1190 | 1191 | 1192 | 1193 | 1194 | 1195 | 1196 | 1197 | 1198 | 1199 | 1200 | 1201 | 1202 | 1203 | 1204 | 1205 | 1206 | 1207 | 1208 | 1209 | 1210 | 1211 | 1212 | 1213 | 1214 | 1215 | 1216 | 1217 | 1218 | 1219 | 1220 | 1221 | 1222 | 1223 | 1224 | 1225 | 1226 | 1227 | 1228 | 1229 | 1230 | 1231 | 1232 | 1233 | 1234 | 1235 | 1236 | 1237 | 1238 | 1239 | 1240 | 1241 | 1242 | 1243 | 1244 | 1245 | 1246 | 1247 | 1248 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/Program.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | using System.IO; 5 | using UnityEngine; 6 | 7 | namespace VectorMap2Opendrive 8 | { 9 | class Program 10 | { 11 | static void Main(string[] args) 12 | { 13 | LoadManager.LoadCSV(); 14 | 15 | int roadCount = LoadManager.GetRoadCount(); 16 | OpenDrive opDrive = new OpenDrive(); 17 | opDrive.roads = new List(roadCount); 18 | 19 | int gldir = -1; // -1 means running on left 20 | 21 | int DIDIndex = 0; 22 | for ( int i = 0; i < roadCount; ++i ) 23 | { 24 | ODRoad road = new ODRoad(); 25 | road.name = i.ToString(); 26 | road.id = i.ToString(); 27 | road.junctionId = "-1"; 28 | road.predecessor = "-1"; 29 | road.successor = "-1"; 30 | road.length = 0; 31 | road.lineGeometries = new List(); 32 | road.elevations = new List(); 33 | road.laneSections = new List(); 34 | 35 | int key = 0; 36 | VM_DtLane nextdtLane = CSVFileManager.Instance().GetstItemByIndex(DIDIndex+1, out key); 37 | float start = 0; 38 | 39 | while ( nextdtLane != null && nextdtLane.Dist != 0 ) 40 | { 41 | VM_DtLane dtlane = CSVFileManager.Instance().GetstItemByIndex(DIDIndex, out key); 42 | VM_Point P = CSVFileManager.Instance().GetstItemByID(dtlane.PID); 43 | VM_Point nextP = CSVFileManager.Instance().GetstItemByID(nextdtLane.PID); 44 | Vector3 vP = new Vector3((float)P.Ly, 0, (float)P.Bx); 45 | Vector3 vNextP = new Vector3((float)nextP.Ly, 0, (float)nextP.Bx); 46 | Vector3 dir = (vNextP - vP).normalized; 47 | Vector3 Zdir = Vector3.Cross(dir, Vector3.up) * gldir; 48 | float offset = gldir == -1 ? dtlane.RW : dtlane.LW; 49 | float nextOffset = gldir == -1 ? nextdtLane.RW : nextdtLane.LW; 50 | 51 | Vector3 road_center_start = vP + Zdir * offset; 52 | Vector3 road_center_end = vNextP + Zdir * nextOffset; 53 | 54 | float secLength = Vector3.Distance(road_center_start, road_center_end); 55 | float hdg = Mathf.Atan2((road_center_end.z - road_center_start.z) , (road_center_end.x - road_center_start.x)); 56 | road.length += secLength; 57 | 58 | // plan geo 59 | PlaneLine planView = new PlaneLine(); 60 | planView.start = start; 61 | planView.xs = road_center_start.x; 62 | planView.ys = road_center_start.z; 63 | planView.hdg = hdg; 64 | planView.length = secLength; 65 | road.lineGeometries.Add(planView); 66 | 67 | // elevation 68 | PolynomCurve ele = new PolynomCurve(); 69 | ele.start = start; 70 | ele.a = (float)P.H; 71 | ele.b = (nextP.H - P.H) / secLength; 72 | ele.c = 0; 73 | ele.d = 0; 74 | road.elevations.Add(ele); 75 | 76 | // lanes 77 | ODLaneSection laneSection = new ODLaneSection(); 78 | laneSection.start = start; 79 | 80 | ODLane center = new ODLane(); 81 | center.id = 0; 82 | 83 | center.predecessor = "-1"; 84 | center.successor = "-1"; 85 | laneSection.center = center; 86 | 87 | laneSection.rights = new List(); 88 | ODLane sideLane = new ODLane(); 89 | sideLane.id = -1; //right; 90 | sideLane.type = "driving"; 91 | sideLane.level = "0"; 92 | sideLane.predecessor = "-1"; 93 | sideLane.successor = "-1"; 94 | sideLane.widths = new List(); 95 | PolynomCurve width = new PolynomCurve(); 96 | width.start = 0; 97 | width.a = dtlane.LW + dtlane.RW; 98 | width.b = ((nextdtLane.LW + nextdtLane.RW) - width.a) / secLength; 99 | width.c = 0; 100 | width.d = 0; 101 | sideLane.widths.Add(width); 102 | laneSection.rights.Add(sideLane); 103 | 104 | road.laneSections.Add(laneSection); 105 | 106 | start += secLength; 107 | 108 | ++DIDIndex; 109 | nextdtLane = CSVFileManager.Instance().GetstItemByIndex(DIDIndex + 1, out key); 110 | } 111 | 112 | opDrive.roads.Add(road); 113 | ++DIDIndex; 114 | } 115 | string path = Directory.GetCurrentDirectory(); 116 | opDrive.SaveToXML(path + "/../../OpenDrive/output.xodr"); 117 | LoadManager.CleanUp(); 118 | } 119 | } 120 | 121 | 122 | public class LoadManager 123 | { 124 | public static string LoadDataFile(string fileName) 125 | { 126 | StreamReader reader = new StreamReader(fileName); 127 | string text = reader.ReadToEnd(); 128 | reader.Close(); 129 | return text; 130 | } 131 | 132 | public static void LoadCSV() 133 | { 134 | string path = Directory.GetCurrentDirectory(); 135 | CSVFileManager.Instance().LoadData(path + "/../../VectorMap/dtLane.csv", LoadDataFile); 136 | CSVFileManager.Instance().LoadData(path + "/../../VectorMap/Lane.csv", LoadDataFile); 137 | CSVFileManager.Instance().LoadData(path + "/../../VectorMap/point.csv", LoadDataFile); 138 | CSVFileManager.Instance().LoadData(path + "/../../VectorMap/node.csv", LoadDataFile); 139 | } 140 | 141 | public static void CleanUp() 142 | { 143 | CSVFileManager.Instance().ClearUp(); 144 | CSVFileManager.Instance().ClearUp(); 145 | CSVFileManager.Instance().ClearUp(); 146 | CSVFileManager.Instance().ClearUp(); 147 | } 148 | 149 | public static int GetRoadCount() 150 | { 151 | int ret = 0; 152 | int dtLaneCount = CSVFileManager.Instance().GetstItemCount(); 153 | for ( int i = 0; i < dtLaneCount; ++i ) 154 | { 155 | int key = -1; 156 | VM_DtLane dtlane = CSVFileManager.Instance().GetstItemByIndex(i, out key); 157 | if (dtlane != null ) 158 | { 159 | if (dtlane.Dist == 0) 160 | ++ret; 161 | } 162 | } 163 | return ret; 164 | } 165 | } 166 | } 167 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/Properties/AssemblyInfo.cs: -------------------------------------------------------------------------------- 1 | using System.Reflection; 2 | using System.Runtime.CompilerServices; 3 | using System.Runtime.InteropServices; 4 | 5 | // General Information about an assembly is controlled through the following 6 | // set of attributes. Change these attribute values to modify the information 7 | // associated with an assembly. 8 | [assembly: AssemblyTitle("VectorMap2Opendrive")] 9 | [assembly: AssemblyDescription("")] 10 | [assembly: AssemblyConfiguration("")] 11 | [assembly: AssemblyCompany("")] 12 | [assembly: AssemblyProduct("VectorMap2Opendrive")] 13 | [assembly: AssemblyCopyright("Copyright © 2019")] 14 | [assembly: AssemblyTrademark("")] 15 | [assembly: AssemblyCulture("")] 16 | 17 | // Setting ComVisible to false makes the types in this assembly not visible 18 | // to COM components. If you need to access a type in this assembly from 19 | // COM, set the ComVisible attribute to true on that type. 20 | [assembly: ComVisible(false)] 21 | 22 | // The following GUID is for the ID of the typelib if this project is exposed to COM 23 | [assembly: Guid("a5b4c1f5-9d4a-4fdc-bbc1-876125f964d8")] 24 | 25 | // Version information for an assembly consists of the following four values: 26 | // 27 | // Major Version 28 | // Minor Version 29 | // Build Number 30 | // Revision 31 | // 32 | // You can specify all the values or you can default the Build and Revision Numbers 33 | // by using the '*' as shown below: 34 | // [assembly: AssemblyVersion("1.0.*")] 35 | [assembly: AssemblyVersion("1.0.0.0")] 36 | [assembly: AssemblyFileVersion("1.0.0.0")] 37 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/UnityEngine.dll: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/monkeykane/VectorMap2Opendrive/304bfed736d95b511da2c83fa133f90789f603c2/VectorMap2Opendrive/UnityEngine.dll -------------------------------------------------------------------------------- /VectorMap2Opendrive/UnityEngine.dll.mdb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/monkeykane/VectorMap2Opendrive/304bfed736d95b511da2c83fa133f90789f603c2/VectorMap2Opendrive/UnityEngine.dll.mdb -------------------------------------------------------------------------------- /VectorMap2Opendrive/VM_DtLane.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | 5 | namespace VectorMap2Opendrive 6 | { 7 | public class VM_DtLane : BaseData 8 | { 9 | public float Dist; 10 | public int PID; 11 | public float Dir; 12 | public float Apara; 13 | public float r; 14 | public float slope; 15 | public float cant; 16 | public float LW; 17 | public float RW; 18 | 19 | public override void LoadData(int nRowIndex, DataFile file) 20 | { 21 | int readIndex = 0; 22 | m_ID = int.Parse(file.getString(readIndex)); readIndex++; 23 | Dist = float.Parse(file.getString(readIndex)); readIndex++; 24 | PID = int.Parse(file.getString(readIndex)); readIndex++; 25 | Dir = float.Parse(file.getString(readIndex)); readIndex++; 26 | Apara = float.Parse(file.getString(readIndex)); readIndex++; 27 | r = float.Parse(file.getString(readIndex)); readIndex++; 28 | slope = float.Parse(file.getString(readIndex)); readIndex++; 29 | cant = float.Parse(file.getString(readIndex)); readIndex++; 30 | LW = float.Parse(file.getString(readIndex)); readIndex++; 31 | RW = float.Parse(file.getString(readIndex)); readIndex++; 32 | } 33 | } 34 | } 35 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/VM_Lane.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | 5 | namespace VectorMap2Opendrive 6 | { 7 | public class VM_Lane : BaseData 8 | { 9 | public int DID; 10 | public int BLID; 11 | public int FLID; 12 | public int BNID; 13 | public int FNID; 14 | public int JCT; 15 | public int BLID2; 16 | public int BLID3; 17 | public int BLID4; 18 | public int FLID2; 19 | public int FLID3; 20 | public int FLID4; 21 | public int ClossID; 22 | public float Span; 23 | public int LCnt; 24 | public int Lno; 25 | public int LaneType; 26 | public float LimitVel; 27 | public float RefVel; 28 | public int RoadSecID; 29 | public int LaneChgFG; 30 | 31 | public override void LoadData(int nRowIndex, DataFile file) 32 | { 33 | int readIndex = 0; 34 | m_ID = int.Parse(file.getString(readIndex)); readIndex++; 35 | DID = int.Parse(file.getString(readIndex)); readIndex++; 36 | BLID = int.Parse(file.getString(readIndex)); readIndex++; 37 | FLID = int.Parse(file.getString(readIndex)); readIndex++; 38 | BNID = int.Parse(file.getString(readIndex)); readIndex++; 39 | FNID = int.Parse(file.getString(readIndex)); readIndex++; 40 | JCT = int.Parse(file.getString(readIndex)); readIndex++; 41 | BLID2 = int.Parse(file.getString(readIndex)); readIndex++; 42 | BLID3 = int.Parse(file.getString(readIndex)); readIndex++; 43 | BLID4 = int.Parse(file.getString(readIndex)); readIndex++; 44 | FLID2 = int.Parse(file.getString(readIndex)); readIndex++; 45 | FLID3 = int.Parse(file.getString(readIndex)); readIndex++; 46 | FLID4 = int.Parse(file.getString(readIndex)); readIndex++; 47 | ClossID = int.Parse(file.getString(readIndex)); readIndex++; 48 | Span = float.Parse(file.getString(readIndex)); readIndex++; 49 | LCnt = int.Parse(file.getString(readIndex)); readIndex++; 50 | Lno = int.Parse(file.getString(readIndex)); readIndex++; 51 | LaneType = int.Parse(file.getString(readIndex)); readIndex++; 52 | LimitVel = float.Parse(file.getString(readIndex)); readIndex++; 53 | RefVel = float.Parse(file.getString(readIndex)); readIndex++; 54 | RoadSecID = int.Parse(file.getString(readIndex)); readIndex++; 55 | LaneChgFG = int.Parse(file.getString(readIndex)); readIndex++; 56 | 57 | } 58 | } 59 | } 60 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/VM_Node.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | 5 | namespace VectorMap2Opendrive 6 | { 7 | public class VM_Node : BaseData 8 | { 9 | public int PID; 10 | 11 | public override void LoadData(int nRowIndex, DataFile file) 12 | { 13 | int readIndex = 0; 14 | m_ID = int.Parse(file.getString(readIndex)); readIndex++; 15 | PID = int.Parse(file.getString(readIndex)); readIndex++; 16 | } 17 | } 18 | } 19 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/VM_Point.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Text; 4 | 5 | namespace VectorMap2Opendrive 6 | { 7 | public class VM_Point : BaseData 8 | { 9 | public double B; 10 | public double L; 11 | public double H; 12 | public double Bx; 13 | public double Ly; 14 | public int ReF; 15 | public int MCODE1; 16 | public int MCODE2; 17 | public int MCODE3; 18 | 19 | public override void LoadData(int nRowIndex, DataFile file) 20 | { 21 | int readIndex = 0; 22 | m_ID = int.Parse(file.getString(readIndex)); readIndex++; 23 | B = double.Parse(file.getString(readIndex)); readIndex++; 24 | L = double.Parse(file.getString(readIndex)); readIndex++; 25 | H = double.Parse(file.getString(readIndex)); readIndex++; 26 | Bx = double.Parse(file.getString(readIndex)); readIndex++; 27 | Ly = double.Parse(file.getString(readIndex)); readIndex++; 28 | ReF = int.Parse(file.getString(readIndex)); readIndex++; 29 | MCODE1 = int.Parse(file.getString(readIndex)); readIndex++; 30 | MCODE2 = int.Parse(file.getString(readIndex)); readIndex++; 31 | MCODE3 = int.Parse(file.getString(readIndex)); readIndex++; 32 | } 33 | } 34 | } 35 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/VectorMap2Opendrive.csproj: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | Debug 6 | AnyCPU 7 | {A5B4C1F5-9D4A-4FDC-BBC1-876125F964D8} 8 | Exe 9 | VectorMap2Opendrive 10 | VectorMap2Opendrive 11 | v3.5 12 | 512 13 | true 14 | 15 | 16 | 17 | AnyCPU 18 | true 19 | full 20 | false 21 | bin\Debug\ 22 | DEBUG;TRACE 23 | prompt 24 | 4 25 | 26 | 27 | AnyCPU 28 | pdbonly 29 | true 30 | bin\Release\ 31 | TRACE 32 | prompt 33 | 4 34 | 35 | 36 | 37 | 38 | 39 | 40 | .\UnityEngine.dll 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/VectorMap2Opendrive.sln: -------------------------------------------------------------------------------- 1 |  2 | Microsoft Visual Studio Solution File, Format Version 12.00 3 | # Visual Studio 15 4 | VisualStudioVersion = 15.0.28307.645 5 | MinimumVisualStudioVersion = 10.0.40219.1 6 | Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "VectorMap2Opendrive", "VectorMap2Opendrive.csproj", "{A5B4C1F5-9D4A-4FDC-BBC1-876125F964D8}" 7 | EndProject 8 | Global 9 | GlobalSection(SolutionConfigurationPlatforms) = preSolution 10 | Debug|Any CPU = Debug|Any CPU 11 | Release|Any CPU = Release|Any CPU 12 | EndGlobalSection 13 | GlobalSection(ProjectConfigurationPlatforms) = postSolution 14 | {A5B4C1F5-9D4A-4FDC-BBC1-876125F964D8}.Debug|Any CPU.ActiveCfg = Debug|Any CPU 15 | {A5B4C1F5-9D4A-4FDC-BBC1-876125F964D8}.Debug|Any CPU.Build.0 = Debug|Any CPU 16 | {A5B4C1F5-9D4A-4FDC-BBC1-876125F964D8}.Release|Any CPU.ActiveCfg = Release|Any CPU 17 | {A5B4C1F5-9D4A-4FDC-BBC1-876125F964D8}.Release|Any CPU.Build.0 = Release|Any CPU 18 | EndGlobalSection 19 | GlobalSection(SolutionProperties) = preSolution 20 | HideSolutionNode = FALSE 21 | EndGlobalSection 22 | GlobalSection(ExtensibilityGlobals) = postSolution 23 | SolutionGuid = {6B1D4DDD-8939-418D-98AF-E99A263E7AAD} 24 | EndGlobalSection 25 | EndGlobal 26 | -------------------------------------------------------------------------------- /VectorMap2Opendrive/app.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | --------------------------------------------------------------------------------