gs.morphs.URDF#

class genesis.options.morphs.URDF(*, pos: tuple = (0.0, 0.0, 0.0), euler: tuple | None = None, quat: tuple | None = None, visualization: bool = True, collision: bool = True, requires_jac_and_IK: bool = True, is_free: bool | None = None, file: Any = '', scale: float | tuple = 1.0, decimate: bool = True, decimate_face_num: int = 500, decimate_aggressiveness: int = 2, convexify: bool | None = None, decompose_nonconvex: bool | None = None, decompose_object_error_threshold: float = 0.15, decompose_robot_error_threshold: float = inf, coacd_options: CoacdOptions | None = None, recompute_inertia: bool = False, fixed: bool = False, prioritize_urdf_material: bool = False, merge_fixed_links: bool = True, links_to_keep: List[str] = [], default_armature: float | None = 0.1)[source]#

Morph loaded from a URDF file. This morph only supports RigidEntity. If you need to create a Drone entity, use gs.morphs.Drone instead.

Note

As part of performance optimization, links connected via a fixed joint are merged if merge_fixed_links is True. This is turned on by default, and can help improve simulation speed without affecting any dynamics and rendering behaviors. However, in cases where certain links are still needed as independent links, such as virtual end-effector links created for being used as IK targets, these links will not be merged if their names are added to links_to_keep. You can also completely turn off link merging by setting merge_fixed_links to False, but it’s recommended to use merge_fixed_links=True in combination with links_to_keep for better performance.

Parameters:
  • file (str) – The path to the file.

  • scale (float or tuple, optional) – The scaling factor for the size of the entity. If a float, it scales uniformly. If a 3-tuple, it scales along each axis. Defaults to 1.0. Note that 3-tuple scaling is only supported for gs.morphs.Mesh.

  • pos (tuple, shape (3,), optional) – The position of the entity in meters as a translational offset. Mathematically, ‘pos’ and ‘euler’ options correspond respectively to the translational and rotational part of a transform that it is (left) applied on the original pose of all floating base links in the kinematic tree indiscriminately. Defaults to (0.0, 0.0, 0.0).

  • euler (tuple, shape (3,), optional) – The euler angles of the entity in degrees as a rotational offset. This follows scipy’s extrinsic x-y-z rotation convention. See ‘pos’ option documentation for details. Defaults to (0.0, 0.0, 0.0).

  • quat (tuple, shape (4,), optional) – The quaternion (w-x-y-z convention) of the entity. If specified, euler will be ignored. Defaults to None.

  • decimate (bool, optional) – Whether to decimate (simplify) the mesh. Defaults to True. This is only used for RigidEntity.

  • decimate_face_num (int, optional) – The number of faces to decimate to. Defaults to 500. This is only used for RigidEntity.

  • decimate_aggressiveness (int) – How hard the decimation process will try to match the target number of faces, as a integer ranging from 0 to 8. 0 is losseless. 2 preserves all features of the original geometry. 5 may significantly alters the original geometry if necessary. 8 does what needs to be done at all costs. Defaults to 5. This is only used for RigidEntity.

  • convexify (bool, optional) – Whether to convexify the entity. When convexify is True, all the meshes in the entity will each be converted to a set of convex hulls. The mesh with be decomposed into multiple convex components if a single one is not sufficient to met the desired accuracy (see ‘decompose_(robot|object)_error_threshold’ documentation). The module ‘coacd’ is used for this decomposition process. If not given, it defaults to True for RigidEntity and False for other deformable entities.

  • decompose_nonconvex (bool, optional) – This parameter is deprecated. Please use ‘convexify’ and ‘decompose_(robot|object)_error_threshold’ instead.

  • decompose_object_error_threshold (bool, optional:) – For basic rigid objects (mug, table…), skip convex decomposition if the relative difference between the volume of original mesh and its convex hull is lower than this threashold. 0.0 to enforce decomposition, float(“inf”) to disable it completely. Defaults to 0.15 (15%).

  • decompose_robot_error_threshold (bool, optional:) – For poly-articulated robots, skip convex decomposition if the relative difference between the volume of original mesh and its convex hull is lower than this threashold. 0.0 to enforce decomposition, float(“inf”) to disable it completely. Defaults to float(“inf”).

  • coacd_options (CoacdOptions, optional) – Options for configuring coacd convex decomposition. Needs to be a gs.options.CoacdOptions object.

  • visualization (bool, optional) – Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision purposes. Defaults to True. visualization and collision cannot both be False.

  • collision (bool, optional) – Whether the entity needs to be considered for collision checking. Defaults to True. visualization and collision cannot both be False.

  • requires_jac_and_IK (bool, optional) – Whether this morph, if created as RigidEntity, requires jacobian and inverse kinematics. Defaults to True.

  • fixed (bool, optional) – Whether the baselink of the entity should be fixed. Defaults to False.

  • prioritize_urdf_material (bool, optional) – Sometimes a geom in a urdf file will be assigned a color, and the geom asset file also contains its own visual material. This parameter controls whether to prioritize the URDF-defined material over the asset’s own material. Defaults to False.

  • merge_fixed_links (bool, optional) – Whether to merge links connected via a fixed joint. Defaults to True.

  • links_to_keep (list of str, optional) – A list of link names that should not be skipped during link merging. Defaults to [].

  • default_armature (float, optional) – Default rotor inertia of the actuators. In practice it is applied to all joints regardless of whether they are actuated. None to disable. Default to 0.1.