public void ExportGeometryData_MeshUnityDecomposer_DefaultGeometry() { // Force runtime mode to set testing package root RuntimeUrdf.runtimeModeEnabled = true; UrdfAssetPathHandler.SetPackageRoot("Packages/com.unity.robotics.urdf-importer/Tests/Runtime/Assets/URDF/cube/"); RuntimeUrdf.runtimeModeEnabled = false; UrdfRobotExtensions.importsettings = ImportSettings.DefaultSettings(); UrdfRobotExtensions.importsettings.convexMethod = ImportSettings.convexDecomposer.unity; var parent = new GameObject("Parent").transform; string path = "package://meshes/cube.stl"; var meshGeometry = new Geometry(mesh: new Mesh(path, new double[] { 1, 1, 1 })); UrdfCollisionExtensions.Create(parent, new Collision(meshGeometry)); UrdfExportPathHandler.SetExportPath("Assets"); var t = parent.GetComponentInChildren <UrdfCollision>().transform.GetChild(0); var export = UrdfGeometry.ExportGeometryData(GeometryTypes.Mesh, t); Assert.IsNotNull(export); Object.DestroyImmediate(parent.gameObject); List <string> outFailedPaths = new List <string>(); AssetDatabase.DeleteAssets(new string[] { "Assets/meshes" }, outFailedPaths); }
public void CheckForUrdfCompatibility_NoChildren_False() { var parent = new GameObject("Parent").transform; Assert.IsFalse(UrdfGeometry.CheckForUrdfCompatibility(parent, GeometryTypes.Box)); Object.DestroyImmediate(parent.gameObject); }
public void IsTransformed_Default_False(Geometry geometry, Vector3 scale, GeometryTypes type) { var parent = new GameObject("Parent").transform; Assert.IsFalse(UrdfGeometry.IsTransformed(parent, UrdfGeometry.GetGeometryType(geometry))); Object.DestroyImmediate(parent.gameObject); }
public void IsTransformed_Rotation_True(Geometry geometry, Vector3 scale, GeometryTypes type) { var parent = new GameObject("Parent").transform; parent.localRotation = Quaternion.Euler(0, 30, 0); Assert.IsTrue(UrdfGeometry.IsTransformed(parent, UrdfGeometry.GetGeometryType(geometry))); Object.DestroyImmediate(parent.gameObject); }
public void IsTransformed_Scale_True(Geometry geometry, Vector3 scale, GeometryTypes type) { var parent = new GameObject("Parent").transform; parent.localScale = Vector3.one * 2f; Assert.IsTrue(UrdfGeometry.IsTransformed(parent, UrdfGeometry.GetGeometryType(geometry))); Object.DestroyImmediate(parent.gameObject); }
public void SetScale_Box_IncreaseLocalScale(Geometry geometry, Vector3 scale, GeometryTypes type) { var parent = new GameObject("Parent").transform; UrdfGeometry.SetScale(parent, geometry, UrdfGeometry.GetGeometryType(geometry)); Assert.AreEqual(scale, parent.transform.localScale); Object.DestroyImmediate(parent.gameObject); }
public void CheckForUrdfCompatibility_UnityPrimitive_True() { var parent = new GameObject("Parent").transform; var child = new GameObject("Child").transform; child.parent = parent; Assert.IsTrue(UrdfGeometry.CheckForUrdfCompatibility(parent, GeometryTypes.Box)); Object.DestroyImmediate(parent.gameObject); }
public void CheckForUrdfCompatibility_Transformed_False() { var parent = new GameObject("Parent").transform; var child = new GameObject("Child").transform; child.parent = parent; child.localPosition = Vector3.one; Assert.IsFalse(UrdfGeometry.CheckForUrdfCompatibility(parent, GeometryTypes.Box)); Object.DestroyImmediate(parent.gameObject); }
public void CheckForUrdfCompatibility_MultipleChildren_False() { var parent = new GameObject("Parent").transform; var child0 = new GameObject("Child0").transform; var child1 = new GameObject("Child1").transform; child0.parent = parent; child1.parent = parent; Assert.IsFalse(UrdfGeometry.CheckForUrdfCompatibility(parent, GeometryTypes.Box)); Object.DestroyImmediate(parent.gameObject); }
public void ExportGeometryData_Sphere_DefaultGeometry() { var parent = new GameObject("Parent").transform; UrdfGeometryCollision.Create(parent, GeometryTypes.Sphere); var t = parent.Find("Sphere"); var export = UrdfGeometry.ExportGeometryData(GeometryTypes.Sphere, t); Assert.IsNotNull(export); Assert.AreEqual(0.5, export.sphere.radius); Assert.AreEqual(typeof(Sphere), export.sphere.GetType()); Assert.IsNull(export.box); Assert.IsNull(export.cylinder); Assert.IsNull(export.mesh); Object.DestroyImmediate(parent.gameObject); }
public void ExportGeometryData_Box_DefaultGeometry() { var parent = new GameObject("Parent").transform; UrdfGeometryCollision.Create(parent, GeometryTypes.Box); var t = parent.Find("Box"); var export = UrdfGeometry.ExportGeometryData(GeometryTypes.Box, t); Assert.IsNotNull(export); Assert.AreEqual(new double[] { 1, 1, 1 }, export.box.size); Assert.AreEqual(typeof(Box), export.box.GetType()); Assert.IsNull(export.cylinder); Assert.IsNull(export.sphere); Assert.IsNull(export.mesh); Object.DestroyImmediate(parent.gameObject); }
public void GenerateConvexMeshes_Cylinder_NullInput() { // Create primitive cylinder with VHACD GameObject geometryGameObject = new GameObject("Cylinder"); MeshFilter meshFilter = geometryGameObject.AddComponent <MeshFilter>(); Link.Geometry.Cylinder cylinder = new Link.Geometry.Cylinder(0.5, 2); //Default unity cylinder sizes meshFilter.sharedMesh = UrdfGeometry.CreateCylinderMesh(cylinder); GameObject go = meshFilter.gameObject; VHACD decomposer = go.AddComponent <VHACD>(); List <Mesh> colliderMeshes = decomposer.GenerateConvexMeshes(null); Assert.IsNotNull(meshFilter.sharedMesh); Assert.IsTrue(colliderMeshes.Count > 0); Component.DestroyImmediate(go.GetComponent <VHACD>()); Object.DestroyImmediate(go.GetComponent <MeshRenderer>()); Object.DestroyImmediate(meshFilter); }
private void DisplayWarnings() { if (!urdfVisual.transform.HasExactlyOneChild()) { GUILayout.Space(5); EditorGUILayout.HelpBox("Visual element must have one and only one child Geometry element.", MessageType.Error); } else if (UrdfGeometry.IsTransformed(urdfVisual.transform.GetChild(0), urdfVisual.geometryType)) { GUILayout.Space(5); EditorGUILayout.HelpBox("Changes to the transform of the child Geometry element cannot be exported to URDF. " + "Make any translation, rotation, or scale changes to this Visual object instead.", MessageType.Error); if (GUILayout.Button("Fix transformations")) { bool transferRotation = urdfVisual.geometryType != GeometryTypes.Mesh; urdfVisual.transform.MoveChildTransformToParent(transferRotation); } } }
public void ExportGeometryData_Cylinder_DefaultGeometry() { // Force runtime mode to avoid creating asset file RuntimeUrdf.runtimeModeEnabled = true; var parent = new GameObject("Parent").transform; UrdfGeometryCollision.Create(parent, GeometryTypes.Cylinder); var t = parent.Find("Cylinder"); var export = UrdfGeometry.ExportGeometryData(GeometryTypes.Cylinder, t); Assert.IsNotNull(export); Assert.AreEqual(0.5, export.cylinder.radius); Assert.AreEqual(2, export.cylinder.length); Assert.AreEqual(typeof(Cylinder), export.cylinder.GetType()); Assert.IsNull(export.box); Assert.IsNull(export.sphere); Assert.IsNull(export.mesh); Object.DestroyImmediate(parent.gameObject); }
public void GetGeometryTypes_All_DefaultEnums(Geometry geometry, Vector3 scale, GeometryTypes type) { Assert.AreEqual(type, UrdfGeometry.GetGeometryType(geometry)); }