public void CreateMatchingMeshCollision_NoVisual_Null() { var visualToCopy = new GameObject("VisualToCopy").transform; var parent = new GameObject("Parent").transform; UrdfGeometryCollision.CreateMatchingMeshCollision(parent, visualToCopy); Assert.AreEqual(0, parent.childCount); Object.DestroyImmediate(parent.gameObject); Object.DestroyImmediate(visualToCopy.gameObject); }
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); }