void ImportRobot() { var urdfFullPath = Path.Combine(Application.dataPath, k_PathUrdf); var robotImporter = UrdfRobotExtensions.Create(urdfFullPath, k_UrdfImportSettings, false); // Create is a coroutine that would usually run only in EditMode, so we need to force its execution here while (robotImporter.MoveNext()) { } // Ensure parameters are set to reasonable values var controller = GameObject.Find(k_NameNiryoOne).GetComponent <Controller>(); controller.stiffness = k_ControllerStiffness; controller.damping = k_ControllerDamping; controller.forceLimit = k_ControllerForceLimit; controller.speed = k_ControllerSpeed; controller.acceleration = k_ControllerAcceleration; GameObject.Find(k_NameBaseLink).GetComponent <ArticulationBody>().immovable = true; #else throw new NotImplementedException( "This integration test can only be executed with the INTEGRATION_TEST scripting define set. " + "The dependencies of this test are not guaranteed to exist in the Project by default."); #endif }
void ImportRobot() { var urdfImportSettings = new ImportSettings { chosenAxis = ImportSettings.axisType.yAxis, convexMethod = ImportSettings.convexDecomposer.unity }; // Import Niryo One with URDF importer var urdfFilepath = Path.Combine(Application.dataPath, k_UrdfRelativeFilepath); // Create is a coroutine that would usually run only in EditMode, so we need to force its execution here var robotImporter = UrdfRobotExtensions.Create(urdfFilepath, urdfImportSettings); while (robotImporter.MoveNext()) { } // Adjust robot parameters var controller = GameObject.Find(k_NiryoOneName).GetComponent <Controller>(); controller.stiffness = k_ControllerStiffness; controller.damping = k_ControllerDamping; controller.forceLimit = k_ControllerForceLimit; controller.speed = k_ControllerSpeed; controller.acceleration = k_ControllerAcceleration; GameObject.Find(k_BaseLinkName).GetComponent <ArticulationBody>().immovable = true; }
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"); }
private void ImportRobot(string urdfFilepath, ImportSettings.convexDecomposer convexDecomposer) { // Import Niryo One by URDF Importer ImportSettings settings = new ImportSettings { choosenAxis = ImportSettings.axisType.yAxis, convexMethod = convexDecomposer, }; UrdfRobotExtensions.Create(urdfFilepath, settings); }
private IEnumerator LoadUrdf() { isLoading = true; if (string.IsNullOrEmpty(urdfFilepath)) { isLoading = false; yield break; } // clear the existing robot to avoid collision if (clearOnLoad && currentRobot != null) { currentRobot.SetActive(false); Destroy(currentRobot); } yield return(null); ImportSettings settings = new ImportSettings { choosenAxis = ImportSettings.axisType.yAxis, convexMethod = useVHACD ? ImportSettings.convexDecomposer.vHACD : ImportSettings.convexDecomposer.unity, }; GameObject robotObject = null; if (showProgress) { IEnumerator <GameObject> createRobot = UrdfRobotExtensions.Create(urdfFilepath, settings, showProgress, true); yield return(createRobot); robotObject = createRobot.Current; } else { robotObject = UrdfRobotExtensions.CreateRuntime(urdfFilepath, settings); } if (robotObject != null && robotObject.transform != null) { robotObject.transform.SetParent(transform); SetControllerParameters(robotObject); Debug.Log("Successfully Loaded URDF" + robotObject.name); } currentRobot = robotObject; isLoading = false; }
public void CreateMatchingMeshCollision_CubeMesh_CopiedCube() { var urdfFile = "Packages/com.unity.robotics.urdf-importer/Tests/Runtime/Assets/URDF/cube/cube.urdf"; UrdfRobotExtensions.importsettings = ImportSettings.DefaultSettings(); UrdfRobotExtensions.importsettings.convexMethod = ImportSettings.convexDecomposer.unity; var robotObject = UrdfRobotExtensions.CreateRuntime(urdfFile, UrdfRobotExtensions.importsettings); Transform visualToCopy = robotObject.transform.Find("base_link/Visuals/unnamed/cube"); var parent = new GameObject("Parent").transform; UrdfGeometryCollision.CreateMatchingMeshCollision(parent, visualToCopy); Assert.AreEqual(1, parent.childCount); var mesh = parent.GetChild(0).gameObject; Assert.IsTrue(mesh.activeInHierarchy); Assert.IsNotNull(mesh.GetComponent <MeshCollider>()); Assert.AreEqual(36, mesh.GetComponent <MeshCollider>().sharedMesh.vertexCount); Assert.IsTrue(Vector3.Distance(Vector3.one * 15f, mesh.GetComponent <MeshCollider>().sharedMesh.bounds.extents) < scaleDelta); Object.DestroyImmediate(parent.gameObject); Object.DestroyImmediate(robotObject.gameObject); }
private static void CreateUrdfObject() { UrdfRobotExtensions.Create(); }
private void OnGUI() { //Styles definitions GUIStyle titleStyle = new GUIStyle(EditorStyles.boldLabel) { alignment = TextAnchor.MiddleLeft, fontSize = 13 }; GUIStyle buttonStyle = new GUIStyle(EditorStyles.miniButtonRight) { fixedWidth = 75 }; //Window title GUILayout.Space(10); GUILayout.Label("Select Axis Type", titleStyle); //Select the original up axis of the imported mesh GUILayout.Space(5); EditorGUILayout.BeginHorizontal(); settings.choosenAxis = (ImportSettings.axisType)EditorGUILayout.EnumPopup( "Select Axis Type", settings.choosenAxis); EditorGUILayout.EndHorizontal(); //Window title GUILayout.Space(10); GUILayout.Label("Select Convex Decomposer", titleStyle); //Select the mesh decomposer GUILayout.Space(5); EditorGUILayout.BeginHorizontal(); settings.convexMethod = (ImportSettings.convexDecomposer)EditorGUILayout.EnumPopup( "Mesh Decomposer", settings.convexMethod); EditorGUILayout.EndHorizontal(); GUILayout.Space(10); settings.OverwriteExistingPrefabs = GUILayout.Toggle(settings.OverwriteExistingPrefabs, "Overwrite Existing Prefabs"); //Import Robot button GUILayout.Space(10); if (GUILayout.Button("Import URDF")) { if (urdfFile != "") { showLoadBar = true; EditorCoroutineUtility.StartCoroutine(UrdfRobotExtensions.Create(urdfFile, settings, showLoadBar), this); } } if (showLoadBar) { float progress = (settings.totalLinks == 0) ? 0 : ((float)settings.linksLoaded / (float)settings.totalLinks); EditorGUI.ProgressBar(new Rect(3, 400, position.width - 6, 20), progress, String.Format("{0}/{1} Links Loaded", settings.linksLoaded, settings.totalLinks)); if (progress == 1) { Close(); } } }
/// <summary> /// Create a prefab from a .urdf file. /// </summary> /// <param name="urdfPath">The path to the .urdf file.</param> /// <param name="settings">Import settings for ROS.</param> /// <param name="immovable">If true, the root object is immovable.</param> private static void CreatePrefab(string urdfPath, ImportSettings settings, bool immovable) { // Import the robot. UrdfRobotExtensions.Create(urdfPath, settings); // Remove irrelevant ROS components. GameObject robot = Object.FindObjectOfType <UrdfRobot>().gameObject; robot.DestroyAll <UrdfJoint>(); robot.DestroyAll <UrdfInertial>(); robot.DestroyAll <UrdfVisuals>(); robot.DestroyAll <UrdfVisual>(); robot.DestroyAll <UrdfCollisions>(); robot.DestroyAll <UrdfCollision>(); robot.DestroyAll <UrdfLink>(); robot.DestroyAll <UrdfRobot>(); robot.DestroyAll <Controller>(); // Destroy unwanted objects. robot.DestroyAllComponents <Light>(); robot.DestroyAllComponents <Camera>(); robot.DestroyAllComponents <UrdfPlugins>(); // Save the generated collider meshes. string collidersDirectory = Path.Combine(Application.dataPath, "collider_meshes", robot.name); if (!Directory.Exists(collidersDirectory)) { Directory.CreateDirectory(collidersDirectory); } foreach (MeshCollider mc in robot.GetComponentsInChildren <MeshCollider>()) { mc.sharedMesh.name = Random.Range(0, 1000000).ToString(); AssetDatabase.CreateAsset(mc.sharedMesh, "Assets/collider_meshes/" + robot.name + "/" + mc.sharedMesh.name); AssetDatabase.SaveAssets(); } // Load the .urdf file. XmlDocument doc = new XmlDocument(); doc.Load(urdfPath); XmlNode xmlRoot = doc.SelectSingleNode("robot"); // Get the prismatic joints. XmlNodeList jointNodes = xmlRoot.SelectNodes("joint"); // The name of each prismatic joint and its axis. Dictionary <string, DriveAxis> prismaticAxes = new Dictionary <string, DriveAxis>(); for (int i = 0; i < jointNodes.Count; i++) { string jointType = jointNodes[i].Attributes["type"].Value.ToLower(); if (jointType == "prismatic") { string jointChild = jointNodes[i].SelectSingleNode("child").Attributes["link"].Value; if (prismaticAxes.ContainsKey(jointChild)) { continue; } Vector3 xyz = jointNodes[i].SelectSingleNode("axis").Attributes["xyz"].Value.xyzToVector3(); DriveAxis driveAxis; // Get the drive axis for a single-axis rotation. if (xyz.x != 0) { driveAxis = DriveAxis.x; } else if (xyz.y != 0) { driveAxis = DriveAxis.y; } else if (xyz.z != 0) { driveAxis = DriveAxis.z; } else { throw new System.Exception("No axis for: " + jointChild); } prismaticAxes.Add(jointChild, driveAxis); } } // Fix the articulation drives.; foreach (ArticulationBody a in robot.GetComponentsInChildren <ArticulationBody>()) { if (a.jointType == ArticulationJointType.RevoluteJoint) { ArticulationDrive drive = a.xDrive; drive.stiffness = 1000; drive.damping = 180; a.xDrive = drive; } // Set the prismatic joint's drive values and expected axis. else if (a.jointType == ArticulationJointType.PrismaticJoint) { DriveAxis da = prismaticAxes[a.name]; ArticulationDrive drive; if (da == DriveAxis.x) { drive = a.xDrive; } else if (da == DriveAxis.y) { drive = a.yDrive; } else { drive = a.zDrive; } drive.forceLimit = a.xDrive.forceLimit; drive.stiffness = 1000; drive.damping = 180; drive.lowerLimit = a.xDrive.lowerLimit; drive.upperLimit = a.xDrive.upperLimit; if (da == DriveAxis.x) { a.linearLockX = ArticulationDofLock.LimitedMotion; a.linearLockY = ArticulationDofLock.LockedMotion; a.linearLockZ = ArticulationDofLock.LockedMotion; a.xDrive = drive; } else if (da == DriveAxis.y) { a.linearLockX = ArticulationDofLock.LockedMotion; a.linearLockY = ArticulationDofLock.LimitedMotion; a.linearLockZ = ArticulationDofLock.LockedMotion; a.yDrive = drive; } else { a.linearLockX = ArticulationDofLock.LockedMotion; a.linearLockY = ArticulationDofLock.LockedMotion; a.linearLockZ = ArticulationDofLock.LimitedMotion; a.zDrive = drive; } ExpectedDriveAxis eda = a.gameObject.AddComponent <ExpectedDriveAxis>(); eda.axis = da; } a.anchorPosition = Vector3.zero; // Set the root articulation body as the root object. if (a.isRoot) { a.immovable = immovable; } } // Destroy redundant ArticulationBodies. ArticulationBody[] badBodies = robot.GetComponentsInChildren <ArticulationBody>(). Where(a => !a.isRoot && a.mass < 0.01f && a.jointType == ArticulationJointType.FixedJoint && a.GetComponentsInChildren <MeshFilter>().Length == 0 && a.GetComponentsInChildren <MeshCollider>().Length == 0). ToArray(); foreach (ArticulationBody b in badBodies) { Object.DestroyImmediate(b.gameObject); } // Get the root object. if (robot.GetComponent <ArticulationBody>() == null) { ArticulationBody[] rootBodies = Object.FindObjectsOfType <ArticulationBody>().Where(a => a.isRoot).ToArray(); if (rootBodies.Length != 1) { Debug.LogError("Root object of the robot doesn't have an ArticulationBody."); } else { rootBodies[0].gameObject.transform.parent = null; rootBodies[0].gameObject.name = robot.name; Object.DestroyImmediate(robot); robot = rootBodies[0].gameObject; } } // Create the prefab directory if it doesn't exist. string absolutePrefabPath = Path.Combine(Application.dataPath, "prefabs"); if (!Directory.Exists(absolutePrefabPath)) { Directory.CreateDirectory(absolutePrefabPath); } // Create the prefab. PrefabUtility.SaveAsPrefabAsset(robot, "Assets/prefabs/" + robot.name + ".prefab"); Object.DestroyImmediate(robot); }
public override void OnInspectorGUI() { if (buttonStyle == null) { buttonStyle = new GUIStyle(EditorStyles.miniButtonRight) { fixedWidth = 75 } } ; urdfRobot = (UrdfRobot)target; EditorGUILayout.PropertyField(axisType, new GUIContent("Axis Type")); serializedObject.ApplyModifiedProperties(); UrdfRobotExtensions.CorrectAxis(urdfRobot.gameObject); GUILayout.Space(5); GUILayout.Label("All Rigidbodies", EditorStyles.boldLabel); DisplaySettingsToggle(new GUIContent("Use Gravity", "If disabled, robot is not affected by gravity."), urdfRobot.SetRigidbodiesUseGravity, UrdfRobot.useGravity); DisplaySettingsToggle(new GUIContent("Use Inertia from URDF", "If disabled, Unity will generate new inertia tensor values automatically."), urdfRobot.SetUseUrdfInertiaData, UrdfRobot.useUrdfInertiaData); DisplaySettingsToggle(new GUIContent("Default Space"), urdfRobot.ChangeToCorrectedSpace, UrdfRobot.changetoCorrectedSpace); GUILayout.Space(5); GUILayout.Label("All Colliders", EditorStyles.boldLabel); DisplaySettingsToggle(new GUIContent("Convex"), urdfRobot.SetCollidersConvex, UrdfRobot.collidersConvex); GUILayout.Space(5); GUILayout.Label("All Joints", EditorStyles.boldLabel); EditorGUILayout.BeginHorizontal(); EditorGUILayout.PrefixLabel("Generate Unique Joint Names"); if (GUILayout.Button("Generate", new GUIStyle(EditorStyles.miniButton) { fixedWidth = 155 })) { urdfRobot.GenerateUniqueJointNames(); } EditorGUILayout.EndHorizontal(); GUILayout.Space(5); EditorGUILayout.PropertyField(axisType, new GUIContent("Axis Type", "Adjust this if the models that make up your robot are facing the wrong direction.")); serializedObject.ApplyModifiedProperties(); UrdfRobotExtensions.CorrectAxis(urdfRobot.gameObject); if (urdfRobot.GetComponent <Unity.Robotics.UrdfImporter.Control.Controller>() == null || urdfRobot.GetComponent <Unity.Robotics.UrdfImporter.Control.FKRobot>() == null) { GUILayout.Label("Components", EditorStyles.boldLabel); GUILayout.BeginHorizontal(); if (GUILayout.Button(urdfRobot.GetComponent <Unity.Robotics.UrdfImporter.Control.Controller>() == null? "Add Controller": "Remove Controller")) { urdfRobot.AddController(); } if (urdfRobot.GetComponent <Unity.Robotics.UrdfImporter.Control.FKRobot>() == null) { if (GUILayout.Button("Add Forward Kinematics")) { urdfRobot.gameObject.AddComponent <Unity.Robotics.UrdfImporter.Control.FKRobot>(); } } GUILayout.EndHorizontal(); } GUILayout.Space(5); GUILayout.Label("URDF Files", EditorStyles.boldLabel); GUILayout.BeginHorizontal(); if (GUILayout.Button("Export robot to URDF")) { exportRoot = EditorUtility.OpenFolderPanel("Select export directory", exportRoot, ""); if (exportRoot.Length == 0) { return; } else if (!Directory.Exists(exportRoot)) { EditorUtility.DisplayDialog("Export Error", "Export root folder must be defined and folder must exist.", "Ok"); } else { urdfRobot.ExportRobotToUrdf(exportRoot); SetEditorPrefs(); } } GUILayout.Space(5); if (GUILayout.Button("Compare URDF Files")) { CompareUrdf window = (CompareUrdf)EditorWindow.GetWindow(typeof(CompareUrdf)); window.minSize = new Vector2(500, 200); window.GetEditorPrefs(); window.Show(); } GUILayout.EndHorizontal(); }