/// <summary> /// Sets collision of a given link when loaded. /// </summary> /// <param name="linkName"></param> /// <param name="urdfVisual"></param> public void SetLinkCollisionLoaded(string linkName, UrdfCollision urdfCollision) { Links.TryGetValue(linkName, out RobotLink link); link?.SetCollisionLoaded(urdfCollision); IsRobotLoaded(); }
public static void Create(Transform parent, GeometryTypes type, Transform visualToCopy = null) { GameObject collisionObject = new GameObject("unnamed"); collisionObject.transform.SetParentAndAlign(parent); UrdfCollision urdfCollision = collisionObject.AddComponent <UrdfCollision>(); urdfCollision.geometryType = type; if (visualToCopy != null) { if (urdfCollision.geometryType == GeometryTypes.Mesh) { UrdfGeometryCollision.CreateMatchingMeshCollision(collisionObject.transform, visualToCopy); } else { UrdfGeometryCollision.Create(collisionObject.transform, type); } //copy transform values from corresponding UrdfVisual collisionObject.transform.position = visualToCopy.position; collisionObject.transform.localScale = visualToCopy.localScale; collisionObject.transform.rotation = visualToCopy.rotation; } else { UrdfGeometryCollision.Create(collisionObject.transform, type); } UnityEditor.EditorGUIUtility.PingObject(collisionObject); }
public static Link.Collision ExportCollisionData(this UrdfCollision urdfCollision) { UrdfGeometry.CheckForUrdfCompatibility(urdfCollision.transform, urdfCollision.geometryType); Link.Geometry geometry = UrdfGeometry.ExportGeometryData(urdfCollision.geometryType, urdfCollision.transform, true); string collisionName = urdfCollision.name == "unnamed" ? null : urdfCollision.name; return(new Link.Collision(geometry, collisionName, UrdfOrigin.ExportOriginData(urdfCollision.transform))); }
public static void Create(Transform parent, Link.Collision collision) { GameObject collisionObject = new GameObject("unnamed"); collisionObject.transform.SetParentAndAlign(parent); UrdfCollision urdfCollision = collisionObject.AddComponent <UrdfCollision>(); urdfCollision.geometryType = UrdfGeometry.GetGeometryType(collision.geometry); UrdfGeometryCollision.Create(collisionObject.transform, urdfCollision.geometryType, collision.geometry); UrdfOrigin.ImportOriginData(collisionObject.transform, collision.origin); }
public override void OnInspectorGUI() { urdfCollisions = (UrdfCollisions)target; GUILayout.Space(10); geometryType = (UrdfGeometry.GeometryTypes)EditorGUILayout.EnumPopup("Type of collision", geometryType); if (GUILayout.Button("Add collision")) { UrdfCollision.Create(urdfCollisions.transform, geometryType); } }
public override void OnInspectorGUI() { urdfCollision = (UrdfCollision)target; GUILayout.Space(5); EditorGUILayout.BeginHorizontal(); EditorGUILayout.PrefixLabel("Geometry Type"); EditorGUILayout.LabelField(urdfCollision.geometryType.ToString()); EditorGUILayout.EndHorizontal(); DisplayWarnings(); }
protected virtual void OnEnable() { obj = (UrdfCollision)serializedObject.targetObject; }
public void SetCollisionLoaded(UrdfCollision urdfCollision) { Collisions[urdfCollision] = true; }