public void Create_FromStlVhacdRuntime_CubeMesh() { // Force runtime mode to set testing package root RuntimeUrdf.runtimeModeEnabled = true; UrdfAssetPathHandler.SetPackageRoot("Packages/com.unity.robotics.urdf-importer/Tests/Runtime/Assets/URDF/cube/"); UrdfRobotExtensions.importsettings = ImportSettings.DefaultSettings(); 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)); // Verify geometry created in Hierarchy var urdfCollision = parent.GetComponentInChildren <UrdfCollision>().transform; var mesh = urdfCollision.Find("cube/cube_0").gameObject; Assert.IsTrue(mesh.activeInHierarchy); Assert.IsNotNull(mesh.GetComponent <MeshCollider>()); Assert.AreEqual(8, mesh.GetComponent <MeshCollider>().sharedMesh.vertexCount); Assert.IsTrue(Vector3.Distance(Vector3.one * 15f, mesh.GetComponent <MeshCollider>().sharedMesh.bounds.extents) < scaleDelta); // Verify geometry created in Assets Assert.IsNotNull(AssetDatabase.FindAssets("cube t:mesh", new string[] { "Packages/com.unity.robotics.urdf-importer/Tests/Runtime/Assets/URDF/cube/meshes" })); AssetDatabase.DeleteAsset("Packages/com.unity.robotics.urdf-importer/Tests/Runtime/Assets/URDF/cube/meshes/cube_1.asset"); Object.DestroyImmediate(parent.gameObject); }
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 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 ExportCollisionsData_DefaultGeometry_DefaultComponents(Geometry geometryBox) { var parent = new GameObject("Parent").transform; var collisions = UrdfCollisionsExtensions.Create(parent, new List <Collision>() { new Collision(geometryBox) }); var urdfColl = collisions.GetComponent <UrdfCollisions>(); Assert.IsTrue(urdfColl.ExportCollisionsData().Count > 0); Object.DestroyImmediate(parent.gameObject); }
public void Create_WithCollisions_DefaultComponents(Geometry geometryBox) { var parent = new GameObject("Parent").transform; var collisions = UrdfCollisionsExtensions.Create(parent, new List <Collision>() { new Collision(geometryBox) }); Assert.IsNotNull(collisions); Assert.IsTrue(parent.GetComponentsInChildren <UrdfCollisions>().Length > 0); Object.DestroyImmediate(parent.gameObject); }
public void Create_LinkCollision_DefaultGeometry() { RuntimeUrdf.runtimeModeEnabled = false; var parent = new GameObject("Parent").transform; var geometry = new Geometry(box: new Box(new double[] { 1, 1, 1 })); var collision = UrdfCollisionExtensions.Create(parent, new Collision(geometry)); Assert.IsNotNull(collision); Assert.IsTrue(collision.gameObject.activeInHierarchy); Assert.AreEqual(GeometryTypes.Box, collision.geometryType); Assert.IsTrue(collision.GetComponentsInChildren <BoxCollider>().Length > 0); Object.DestroyImmediate(parent.gameObject); }
public void GetGeometryTypes_All_DefaultEnums(Geometry geometry, Vector3 scale, GeometryTypes type) { Assert.AreEqual(type, UrdfGeometry.GetGeometryType(geometry)); }