private void OnGUI() { // styles var titleLabelStyle = new GUIStyle(GUI.skin.label) { alignment = TextAnchor.MiddleCenter, fontSize = 14 }; var subtitleLabelStyle = new GUIStyle(GUI.skin.label) { alignment = TextAnchor.MiddleCenter, fontSize = 10 }; GUILayout.Space(10); EditorGUILayout.LabelField("HD Map Export", titleLabelStyle, GUILayout.ExpandWidth(true)); GUILayout.Space(5); EditorGUILayout.LabelField("", GUI.skin.horizontalSlider); GUILayout.Space(10); EditorGUILayout.HelpBox("Settings", UnityEditor.MessageType.Info); var selectedNew = EditorGUILayout.Popup("Export Format", Selected, exportFormats); GUILayout.Space(10); if (Selected != selectedNew) { FileName = ""; Selected = selectedNew; } if (exportFormats[Selected] == "Apollo 5 HD Map") { EditorGUILayout.HelpBox("Save File As...", UnityEditor.MessageType.Info); GUILayout.BeginHorizontal(); FileName = EditorGUILayout.TextField(FileName); var directoryName = string.IsNullOrWhiteSpace(FileName) ? "" : Path.GetDirectoryName(FileName); if (GUILayout.Button("...", GUILayout.ExpandWidth(false))) { var path = EditorUtility.SaveFilePanel("Save Apollo HD Map as BIN File", directoryName, "base_map.bin", "bin"); if (!string.IsNullOrEmpty(path)) { FileName = path; } } GUILayout.EndHorizontal(); } else if (exportFormats[Selected] == "Autoware Vector Map") { EditorGUILayout.HelpBox("Select Folder to Save...", UnityEditor.MessageType.Info); GUILayout.BeginHorizontal(); FileName = EditorGUILayout.TextField(FileName); if (GUILayout.Button("...", GUILayout.ExpandWidth(false))) { var path = EditorUtility.SaveFolderPanel("Select Folder to Save Autoware Vector Map", FileName, "AutowareVectorMap"); if (!string.IsNullOrEmpty(path)) { FileName = path; } } GUILayout.EndHorizontal(); } else if (exportFormats[Selected] == "Lanelet2 Map") { EditorGUILayout.HelpBox("Save File As...", UnityEditor.MessageType.Info); GUILayout.BeginHorizontal(); FileName = EditorGUILayout.TextField(FileName); var directoryName = string.IsNullOrWhiteSpace(FileName) ? "" : Path.GetDirectoryName(FileName); if (GUILayout.Button("...", GUILayout.ExpandWidth(false))) { var path = EditorUtility.SaveFilePanel("Save Lanelet2 Map as XML File", directoryName, "lanelet2.osm", "osm"); if (!string.IsNullOrEmpty(path)) { FileName = path; } } GUILayout.EndHorizontal(); } else if (exportFormats[Selected] == "OpenDRIVE Map") { EditorGUILayout.HelpBox("Save File As...", UnityEditor.MessageType.Info); GUILayout.BeginHorizontal(); FileName = EditorGUILayout.TextField(FileName); var directoryName = string.IsNullOrWhiteSpace(FileName) ? "" : Path.GetDirectoryName(FileName); if (GUILayout.Button("...", GUILayout.ExpandWidth(false))) { var path = EditorUtility.SaveFilePanel("Save OpenDRIVE Map as xodr File", directoryName, "OpenDRIVE.xodr", "xodr"); if (!string.IsNullOrEmpty(path)) { FileName = path; } } GUILayout.EndHorizontal(); } if (GUILayout.Button(new GUIContent("Export", $"Export {exportFormats[Selected]}"))) { if (string.IsNullOrEmpty(FileName)) { EditorUtility.DisplayDialog("Error", "Please specify output file/folder name!", "OK"); return; } if (exportFormats[Selected] == "Apollo 5 HD Map") { ApolloMapTool apolloMapTool = new ApolloMapTool(); apolloMapTool.Export(FileName); } else if (exportFormats[Selected] == "Autoware Vector Map") { AutowareMapTool autowareMapTool = new AutowareMapTool(); autowareMapTool.Export(FileName); } else if (exportFormats[Selected] == "Lanelet2 Map") { Lanelet2MapExporter lanelet2MapExporter = new Lanelet2MapExporter(); lanelet2MapExporter.Export(FileName); } else if (exportFormats[Selected] == "OpenDRIVE Map") { OpenDriveMapExporter openDriveMapExporter = new OpenDriveMapExporter(); openDriveMapExporter.Export(FileName); } } }
public void ExportImport() { var environments = Path.Combine(Application.dataPath, "External", "Environments"); var temp = Path.Combine(Application.dataPath, "..", "Temp"); LogAssert.ignoreFailingMessages = true; try { foreach (var path in Directory.EnumerateDirectories(environments)) { var map = Path.GetFileName(path); if (map.EndsWith("@tmp")) { // skip dummy folders Jenkins creates continue; } if (File.Exists(Path.Combine(path, ".skiptest"))) { Debug.LogWarning($"Skipping {map}"); continue; } Debug.LogWarning($"****** Testing {map}"); var scene = EditorSceneManager.OpenScene(Path.Combine(environments, map, $"{map}.unity")); // export var autoware = new AutowareMapTool(); autoware.Export(Path.Combine(temp, $"{map}_autoware")); var apollo3 = new ApolloMapTool(ApolloMapTool.ApolloVersion.Apollo_3_0); apollo3.Export(Path.Combine(temp, $"{map}_apollo3")); Assert.IsFalse(scene.isDirty); var apollo5 = new ApolloMapTool(ApolloMapTool.ApolloVersion.Apollo_5_0); apollo5.Export(Path.Combine(temp, $"{map}_apollo5")); Assert.IsFalse(scene.isDirty); var opendrive = new OpenDriveMapExporter(); opendrive.Export(Path.Combine(temp, $"{map}_opendrive")); Assert.IsFalse(scene.isDirty); var lanelet = new Lanelet2MapExporter(); lanelet.Export(Path.Combine(temp, $"{map}_lanelet2")); Assert.IsFalse(scene.isDirty); // import EditorSceneManager.NewScene(NewSceneSetup.DefaultGameObjects); var apolloImport = new ApolloMapImporter(10f, 0.5f, true); apolloImport.Import(Path.Combine(temp, $"{map}_apollo5")); EditorSceneManager.NewScene(NewSceneSetup.DefaultGameObjects); var opendriveImport = new OpenDriveMapImporter(10f, 0.5f, true); opendriveImport.Import(Path.Combine(temp, $"{map}_opendrive")); EditorSceneManager.NewScene(NewSceneSetup.DefaultGameObjects); var laneletImport = new Lanelet2MapImporter(true); laneletImport.Import(Path.Combine(temp, $"{map}_lanelet2")); } } finally { EditorSceneManager.NewScene(NewSceneSetup.DefaultGameObjects); LogAssert.ignoreFailingMessages = false; } }