// 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);
        }
        // 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);
            }
        }
        /// <summary>
        /// Create a Robot gameobject from filename in runtime.
        /// It is a synchronous (blocking) function and only returns after the gameobject has been created.
        /// </summary>
        /// <param name="filename">URDF filename</param>
        /// <param name="settings">Import Settings</param>
        /// <returns> Robot game object</returns>
        public static GameObject CreateRuntime(string filename, ImportSettings settings)
        {
            ImportPipelineData im = ImportPipelineInit(filename, settings, false, true);

            if (im == null)
            {
                return(null);
            }

            ImportPipelineCreateObject(im);

            while (ProcessJointStack(im))
            {// process the stack until finished.
            }

            ImportPipelinePostCreate(im);

            return(im.robotGameObject);
        }
        /// <summary>
        /// Coroutine to create a Robot game object from the urdf file
        /// </summary>
        /// <param name="filename">URDF filename</param>
        /// <param name="settings">Import Settings</param>
        /// <param name="loadStatus">If true, will show the progress of import step by step</param>
        /// <param name="forceRuntimeMode">
        /// When true, runs the runtime loading mode even in Editor. When false, uses the default behavior,
        /// i.e. runtime will be enabled in standalone build and disable when running in editor.
        /// In runtime mode, the Controller component of the robot will be added but not activated automatically and has to be enabled manually.
        /// This is to allow initializing the controller values (stiffness, damping, etc.) before the controller.Start() is called
        /// </param>
        /// <returns></returns>
        public static IEnumerator <GameObject> Create(string filename, ImportSettings settings, bool loadStatus = false, bool forceRuntimeMode = false)
        {
            ImportPipelineData im = ImportPipelineInit(filename, settings, loadStatus, forceRuntimeMode);

            if (im == null)
            {
                yield break;
            }

            ImportPipelineCreateObject(im);

            while (ProcessJointStack(im))
            {
                if (loadStatus)
                {
                    yield return(null);
                }
            }

            ImportPipelinePostCreate(im);
            yield return(im.robotGameObject);
        }
        // Creates the stack of robot joints. Should be called iteratively until false is returned.
        private static bool ProcessJointStack(ImportPipelineData im)
        {
            if (im.importStack == null)
            {
                im.importStack = new Stack <Tuple <Link, Transform, Joint> >();
                im.importStack.Push(new Tuple <Link, Transform, Joint>(im.robot.root, im.robotGameObject.transform, null));
            }

            if (im.importStack.Count != 0)
            {
                Tuple <Link, Transform, Joint> currentLink = im.importStack.Pop();
                GameObject importedLink = UrdfLinkExtensions.Create(currentLink.Item2, currentLink.Item1, currentLink.Item3);
                im.settings.linksLoaded++;
                foreach (Joint childJoint in currentLink.Item1.joints)
                {
                    Link child = childJoint.ChildLink;
                    im.importStack.Push(new Tuple <Link, Transform, Joint>(child, importedLink.transform, childJoint));
                }
                return(true);
            }
            return(false);
        }
        // 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);
        }