// Initializes import pipeline and reads the urdf file. private static ImportPipelineData ImportPipelineInit(string filename, ImportSettings settings, bool loadStatus, bool forceRuntimeMode) { ImportPipelineData im = new ImportPipelineData(); im.settings = settings; im.loadStatus = loadStatus; im.wasRuntimeMode = RuntimeUrdf.IsRuntimeMode(); im.forceRuntimeMode = forceRuntimeMode; if (forceRuntimeMode) { RuntimeUrdf.SetRuntimeMode(true); } im.robot = new Robot(filename); if (!UrdfAssetPathHandler.IsValidAssetPath(im.robot.filename)) { Debug.LogError("URDF file and ressources must be placed in Assets Folder:\n" + Application.dataPath); if (forceRuntimeMode) { // set runtime mode back to what it was RuntimeUrdf.SetRuntimeMode(im.wasRuntimeMode); } return(null); } return(im); }
public void AssetDatabase_LoadAssetAtPath_Object() { RuntimeUrdf.SetRuntimeMode(false); string path = "Packages/com.unity.robotics.urdf-importer/Tests/Runtime/RuntimeImport/RuntimeUrdfTests.cs"; Assert.IsNotNull(RuntimeUrdf.AssetDatabase_LoadAssetAtPath(path, typeof(UnityEngine.Object))); }
public void SetUp() { // a robot tag needs to be added in project settings before runtime import can work RuntimeUrdf.SetRuntimeMode(false); UrdfRobotExtensions.CreateTag(); RuntimeUrdf.AssetDatabase_CreateFolder("Assets", "Tests"); RuntimeUrdf.AssetDatabase_CreateFolder("Assets/Tests", "Runtime"); RuntimeUrdf.AssetDatabase_CreateFolder("Assets/Tests/Runtime", "GeometryTests"); }
public void AssetExists_False() { RuntimeUrdf.SetRuntimeMode(false); Assert.IsFalse(RuntimeUrdf.AssetExists($"{createAssetPath}/tEstAsset.Prefab")); // case Assert.IsFalse(RuntimeUrdf.AssetExists($"{createAssetPath}/TestAsset.prefabs", true)); Assert.IsFalse(RuntimeUrdf.AssetExists($"{createAssetPath}/TestAsset.prefa", true)); Assert.IsFalse(RuntimeUrdf.AssetExists($"{createAssetPath}/estAsset.prefab", true)); Assert.IsFalse(RuntimeUrdf.AssetExists($"{createAssetPath}/sub/TestAsset.prefab", true)); }
// Post creation stuff: add to parent, fix axis and add collision exceptions. private static void ImportPipelinePostCreate(ImportPipelineData im) { #if UNITY_EDITOR GameObjectUtility.SetParentAndAlign(im.robotGameObject, Selection.activeObject as GameObject); Undo.RegisterCreatedObjectUndo(im.robotGameObject, "Create " + im.robotGameObject.name); Selection.activeObject = im.robotGameObject; #endif CorrectAxis(im.robotGameObject); CreateCollisionExceptions(im.robot, im.robotGameObject); if (im.forceRuntimeMode) { // set runtime mode back to what it was RuntimeUrdf.SetRuntimeMode(im.wasRuntimeMode); } }
public void SetUp() { m_StlCubeCopyPath = k_AssetRoot + "/cube.stl"; RuntimeUrdf.SetRuntimeMode(false); Directory.CreateDirectory(k_AssetRoot); }
public void SetRuntimeMode_False() { RuntimeUrdf.SetRuntimeMode(false); Assert.IsFalse(RuntimeUrdf.IsRuntimeMode()); }
public void AssetExists_True() { RuntimeUrdf.SetRuntimeMode(false); Assert.IsTrue(RuntimeUrdf.AssetExists($"{createAssetPath}/TestAsset.prefab")); Assert.IsTrue(RuntimeUrdf.AssetExists($"{createAssetPath}/tEstAsset.Prefab", true)); }