static Material defaultMaterial = null; // used RuntimeURDF
        private static void CreateDefaultMaterial()
        {
            Material material = defaultMaterial;

#if UNITY_EDITOR
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                material = RuntimeUrdf.AssetDatabase_LoadAssetAtPath <Material>(UrdfAssetPathHandler.GetMaterialAssetPath(DefaultMaterialName));
            }
#endif
            if (material != null)
            {
                return;
            }

            material = MaterialExtensions.CreateBasicMaterial();
            MaterialExtensions.SetMaterialColor(material, new Color(0.33f, 0.33f, 0.33f, 0.0f));

            // just keep it in memory while the app is running.
            defaultMaterial = material;
#if UNITY_EDITOR
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                // create the material to be reused
                RuntimeUrdf.AssetDatabase_CreateAsset(material, UrdfAssetPathHandler.GetMaterialAssetPath(DefaultMaterialName));
            }
#endif
        }
        // 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 static void SetUrdfMaterial(GameObject gameObject, Link.Visual.Material urdfMaterial)
        {
            if (urdfMaterial != null)
            {
                var material = CreateMaterial(urdfMaterial);
                SetMaterial(gameObject, material);
            }
            else
            {
                //If the URDF material is not defined, and the renderer is missing
                //a material, assign the default material.
                Renderer renderer = gameObject.GetComponentInChildren <Renderer>();
                if (renderer != null && renderer.sharedMaterial == null)
                {
                    Material material = defaultMaterial;
#if UNITY_EDITOR
                    if (!RuntimeUrdf.IsRuntimeMode())
                    {
                        material = RuntimeUrdf.AssetDatabase_LoadAssetAtPath <Material>(UrdfAssetPathHandler.GetMaterialAssetPath(DefaultMaterialName));
                    }
#endif
                    SetMaterial(gameObject, material);
                }
            }
        }
Esempio n. 4
0
        private static GameObject CreateMeshVisual(Link.Geometry.Mesh mesh)
        {
#if UNITY_EDITOR
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                GameObject meshObject = LocateAssetHandler.FindUrdfAsset <GameObject>(mesh.filename);
                return(meshObject == null ? null : (GameObject)RuntimeUrdf.PrefabUtility_InstantiatePrefab(meshObject));
            }
#endif
            return(CreateMeshVisualRuntime(mesh));
        }
Esempio n. 5
0
        public static bool IsValidAssetPath(string path)
        {
#if UNITY_EDITOR
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                return(GetRelativeAssetPath(path) != null);
            }
#endif
            //RuntimeImporter. TODO: check if the path really exists
            return(true);
        }
Esempio n. 6
0
        private static void ConvertMeshToColliders(GameObject gameObject, string location = null, bool setConvex = true)
        {
            MeshFilter[] meshFilters = gameObject.GetComponentsInChildren <MeshFilter>();
            if (UrdfRobotExtensions.importsettings.convexMethod == ImportSettings.convexDecomposer.unity)
            {
                foreach (MeshFilter meshFilter in meshFilters)
                {
                    GameObject   child        = meshFilter.gameObject;
                    MeshCollider meshCollider = child.AddComponent <MeshCollider>();
                    meshCollider.sharedMesh = meshFilter.sharedMesh;

                    meshCollider.convex = setConvex;

                    Object.DestroyImmediate(child.GetComponent <MeshRenderer>());
                    Object.DestroyImmediate(meshFilter);
                }
            }
            else
            {
                string templateFileName = "";
                string filePath         = "";
                int    meshIndex        = 0;
                if (!RuntimeUrdf.IsRuntimeMode() && location != null)
                {
                    string meshFilePath = UrdfAssetPathHandler.GetRelativeAssetPathFromUrdfPath(location, false);
                    templateFileName = Path.GetFileNameWithoutExtension(meshFilePath);
                    filePath         = Path.GetDirectoryName(meshFilePath);
                }

                foreach (MeshFilter meshFilter in meshFilters)
                {
                    GameObject  child          = meshFilter.gameObject;
                    VHACD       decomposer     = child.AddComponent <VHACD>();
                    List <Mesh> colliderMeshes = decomposer.GenerateConvexMeshes(meshFilter.sharedMesh);
                    foreach (Mesh collider in colliderMeshes)
                    {
                        if (!RuntimeUrdf.IsRuntimeMode())
                        {
                            meshIndex++;
                            string name = $"{filePath}/{templateFileName}_{meshIndex}.asset";
                            Debug.Log($"Creating new mesh file: {name}");
                            RuntimeUrdf.AssetDatabase_CreateAsset(collider, name);
                            RuntimeUrdf.AssetDatabase_SaveAssets();
                        }
                        MeshCollider current = child.AddComponent <MeshCollider>();
                        current.sharedMesh = collider;
                        current.convex     = setConvex;
                    }
                    Component.DestroyImmediate(child.GetComponent <VHACD>());
                    Object.DestroyImmediate(child.GetComponent <MeshRenderer>());
                    Object.DestroyImmediate(meshFilter);
                }
            }
        }
Esempio n. 7
0
        private static Material GetDefaultDiffuseMaterial()
        {
#if UNITY_EDITOR
            // also save the material in the Assets
            if (!RuntimeUrdf.IsRuntimeMode() && MaterialExtensions.GetRenderPipelineType() == MaterialExtensions.RenderPipelineType.Standard)
            {
                s_DefaultDiffuse = RuntimeUrdf.AssetDatabase_GetBuiltinExtraResource <Material>("Default-Diffuse.mat");
            }
#endif
            if (s_DefaultDiffuse)
            {   // Could't use the "Default-Diffuse.mat", either because of HDRP or runtime. so let's create one.
                s_DefaultDiffuse = MaterialExtensions.CreateBasicMaterial();
            }
            return(s_DefaultDiffuse);
        }
Esempio n. 8
0
        public static string GetRelativeAssetPath(string absolutePath)
        {
            var absolutePathUnityFormat = absolutePath.SetSeparatorChar();

            if (!absolutePathUnityFormat.StartsWith(Application.dataPath.SetSeparatorChar()))
            {
#if UNITY_EDITOR
                if (!RuntimeUrdf.IsRuntimeMode())
                {
                    return(null);
                }
#endif
                return(absolutePath); // so that it works in runtime
            }

            var assetPath = "Assets" + absolutePath.Substring(Application.dataPath.Length);
            return(assetPath.SetSeparatorChar());
        }
Esempio n. 9
0
        private static GameObject CreateMeshCollider(Link.Geometry.Mesh mesh)
        {
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                GameObject prefabObject = LocateAssetHandler.FindUrdfAsset <GameObject>(mesh.filename);
                if (prefabObject == null)
                {
                    Debug.LogError("Unable to create mesh collider for the mesh: " + mesh.filename);
                    return(null);
                }

                GameObject meshObject = (GameObject)RuntimeUrdf.PrefabUtility_InstantiatePrefab(prefabObject);
                ConvertMeshToColliders(meshObject, location: mesh.filename);

                return(meshObject);
            }
            return(CreateMeshColliderRuntime(mesh));
        }
Esempio n. 10
0
        private static void ConvertCylinderToCollider(MeshFilter filter)
        {
            GameObject go       = filter.gameObject;
            var        collider = filter.sharedMesh;

            // Only create an asset if not runtime import
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                var packageRoot = UrdfAssetPathHandler.GetPackageRoot();
                var filePath    = RuntimeUrdf.AssetDatabase_GUIDToAssetPath(RuntimeUrdf.AssetDatabase_CreateFolder($"{packageRoot}", "meshes"));
                var name        = $"{filePath}/Cylinder.asset";
                Debug.Log($"Creating new cylinder file: {name}");
                RuntimeUrdf.AssetDatabase_CreateAsset(collider, name, uniquePath: true);
                RuntimeUrdf.AssetDatabase_SaveAssets();
            }
            MeshCollider current = go.AddComponent <MeshCollider>();

            current.sharedMesh = collider;
            current.convex     = true;
            Object.DestroyImmediate(go.GetComponent <MeshRenderer>());
            Object.DestroyImmediate(filter);
        }
        public static void CreateTag()
        {
#if UNITY_EDITOR
            if (RuntimeUrdf.IsRuntimeMode())
            {
                // This is to make the behavior consistent with Runtime mode
                // as tags cannot be created in a Standalone build.
                return;
            }

            // Open tag manager
            SerializedObject   tagManager = new SerializedObject(AssetDatabase.LoadAllAssetsAtPath("ProjectSettings/TagManager.asset")[0]);
            SerializedProperty tagsProp   = tagManager.FindProperty("tags");


            // First check if it is not already present
            bool found = false;
            for (int i = 0; i < tagsProp.arraySize; i++)
            {
                SerializedProperty t = tagsProp.GetArrayElementAtIndex(i);
                if (t.stringValue.Equals(FKRobot.k_TagName))
                {
                    found = true;
                    break;
                }
            }

            // if not found, add it
            if (!found)
            {
                tagsProp.InsertArrayElementAtIndex(0);
                SerializedProperty n = tagsProp.GetArrayElementAtIndex(0);
                n.stringValue = FKRobot.k_TagName;
            }

            tagManager.ApplyModifiedProperties();
#endif
        }
        public void OnPreprocessModel()
        {
#if UNITY_EDITOR
            if (!RuntimeUrdf.IsRuntimeMode())
            {
                ModelImporter modelImporter = (ModelImporter)assetImporter;
                isCollada = Path.GetExtension(modelImporter.assetPath).ToLowerInvariant() == ".dae";

                if (!isCollada)
                {
                    return;
                }

                if (modelImporter.useFileScale)
                {
                    modelImporter.globalScale = ReadGlobalScale(getAbsolutePath(modelImporter.assetPath));
                }
                modelImporter.animationType = ModelImporterAnimationType.None;
                modelImporter.importCameras = false;
                modelImporter.importLights  = false;
                orientation = readColladaOrientation(getAbsolutePath(modelImporter.assetPath));
            }
#endif
        }
        // Creates the robot game object.
        private static void ImportPipelineCreateObject(ImportPipelineData im)
        {
            im.robotGameObject = new GameObject(im.robot.name);

            importsettings         = im.settings;
            im.settings.totalLinks = im.robot.links.Count;

            CreateTag();
            SetTag(im.robotGameObject);

            im.robotGameObject.AddComponent <UrdfRobot>();

            im.robotGameObject.AddComponent <Unity.Robotics.UrdfImporter.Control.Controller>();
            if (RuntimeUrdf.IsRuntimeMode())
            {// In runtime mode, we have to disable controller while robot is being constructed.
                im.robotGameObject.GetComponent <Unity.Robotics.UrdfImporter.Control.Controller>().enabled = false;
            }

            im.robotGameObject.GetComponent <UrdfRobot>().SetAxis(im.settings.choosenAxis);

            UrdfAssetPathHandler.SetPackageRoot(Path.GetDirectoryName(im.robot.filename));
            UrdfMaterial.InitializeRobotMaterials(im.robot);
            UrdfPlugins.Create(im.robotGameObject.transform, im.robot.plugins);
        }
Esempio n. 14
0
 public void SetRuntimeMode_False()
 {
     RuntimeUrdf.SetRuntimeMode(false);
     Assert.IsFalse(RuntimeUrdf.IsRuntimeMode());
 }
Esempio n. 15
0
 public void IsRuntimeMode_True()
 {
     RuntimeUrdf.runtimeModeEnabled = true;
     Assert.IsTrue(RuntimeUrdf.IsRuntimeMode());
 }