public void Create_CylinderMesh_AssetCreated() { // Force runtime mode to set testing package root RuntimeUrdf.runtimeModeEnabled = true; UrdfAssetPathHandler.SetPackageRoot("Assets/Tests/Runtime/GeometryTests"); RuntimeUrdf.runtimeModeEnabled = false; var parent = new GameObject("Parent").transform; UrdfGeometryCollision.Create(parent, GeometryTypes.Cylinder); // Verify Cylinder created in Hierarchy var createdCylinder = parent.Find("Cylinder").gameObject; Assert.IsTrue(createdCylinder.activeInHierarchy); Assert.IsNotNull(createdCylinder.GetComponent <MeshCollider>()); // Check for standard values on collider Assert.AreEqual(1864, createdCylinder.GetComponent <MeshCollider>().sharedMesh.vertexCount); Assert.IsTrue(Vector3.Distance(Vector3.zero, createdCylinder.GetComponent <MeshCollider>().sharedMesh.bounds.center) < centerDelta); Assert.IsTrue(Vector3.Distance(new Vector3(0.5f, 1f, 0.5f), createdCylinder.GetComponent <MeshCollider>().sharedMesh.bounds.extents) < scaleDelta); // Verify Cylinder created in Assets Assert.IsNotNull(RuntimeUrdf.AssetDatabase_FindAssets("Cylinder t:mesh", new string[] { "Assets/Tests/Runtime/GeometryTests" })); AssetDatabase.DeleteAsset("Assets/Tests/Runtime/GeometryTests/Cylinder.asset"); Object.DestroyImmediate(parent.gameObject); }
public void Create_Mesh_UnityPrimitive() { var parent = new GameObject("Parent").transform; UrdfGeometryCollision.Create(parent, GeometryTypes.Mesh); // Verify geometry created in Hierarchy var mesh = parent.Find("Mesh").gameObject; Assert.IsTrue(mesh.activeInHierarchy); Assert.IsNotNull(mesh.GetComponent <MeshCollider>()); Assert.AreEqual(new Bounds(Vector3.zero, Vector3.zero), mesh.GetComponent <MeshCollider>().bounds); Object.DestroyImmediate(parent.gameObject); }
public void Create_Sphere_UnityPrimitive() { var parent = new GameObject("Parent").transform; UrdfGeometryCollision.Create(parent, GeometryTypes.Sphere); // Verify geometry created in Hierarchy var sphere = parent.Find("Sphere").gameObject; Assert.IsTrue(sphere.activeInHierarchy); Assert.IsNotNull(sphere.GetComponent <SphereCollider>()); Assert.AreEqual(new Bounds(Vector3.zero, Vector3.one), sphere.GetComponent <SphereCollider>().bounds); 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 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); }