gs.morphs.Mesh#

class genesis.options.morphs.Mesh(*, order: int = 1, mindihedral: int = 10, minratio: float = 1.1, nobisect: bool = True, quality: bool = True, maxvolume: float = -1.0, verbose: int = 0, force_retet: bool = False, 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 = False, 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, parse_glb_with_trimesh: bool = False, parse_glb_with_zup: bool = False, fixed: bool = False, contype: int = 65535, conaffinity: int = 65535, group_by_material: bool = True, merge_submeshes_for_collision: bool = True)[source]#

Morph loaded from a mesh file.

Note

In order to speed up simulation, the loaded mesh will first be decimated (simplified) to a target number of faces, followed by convexification (for collision mesh only). Such process can be disabled by setting decimate and convexify to False.

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. Defaults to (0.0, 0.0, 0.0).

  • euler (tuple, shape (3,), optional) – The euler angle of the entity in degrees. This follows scipy’s extrinsic x-y-z rotation convention. 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.

  • merge_submeshes_for_collision (bool, optional) – Whether to merge submeshes for collision. Defaults to True. This is only used for RigidEntity.

  • 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. This is only used for RigidEntity.

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

  • requires_jac_and_IK (bool, optional) – Whether this morph, if created as RigidEntity, requires jacobian and inverse kinematics. Defaults to False. This is only used for RigidEntity.

  • parse_glb_with_trimesh (bool, optional) – Whether to use trimesh to load glb files. Defaults to False, in which case pygltflib will be used.

  • parse_glb_with_zup (bool, optional) – Whether to use zup to load glb files. Defaults to False.

  • fixed (bool, optional) – Whether the baselink of the entity should be fixed. Defaults to False. This is only used for RigidEntity.

  • contype (int, optional) – The 32-bit integer bitmasks used for contact filtering of contact pairs. When the contype of one geom and the conaffinity of the other geom share a common bit set to 1, two geoms can collide. Defaults to 0xFFFF.

  • conaffinity (int, optional) – The 32-bit integer bitmasks used for contact filtering of contact pairs. When the conaffinity of one geom and the contype of the other geom share a common bit set to 1, two geoms can collide. Defaults to 0xFFFF.

  • group_by_material (bool, optional) – Whether to group submeshes by their visual material type defined in the asset file. Defaults to True. This is only used for RigidEntity.

  • order (int, optional) – The order of the FEM mesh. Defaults to 1. This is only used for FEMEntity.

  • mindihedral (int, optional) – The minimum dihedral angle in degrees during tetraheralization. Defaults to 10. This is only used for Volumetric Entity that requires tetraheralization.

  • minratio (float, optional) – The minimum tetrahedron quality ratio during tetraheralization. Defaults to 1.1. This is only used for Volumetric Entity that requires tetraheralization.

  • nobisect (bool, optional) – Whether to disable bisection during tetraheralization. Defaults to True. This is only used for Volumetric Entity that requires tetraheralization.

  • quality (bool, optional) – Whether to improve quality during tetraheralization. Defaults to True. This is only used for Volumetric Entity that requires tetraheralization.

  • maxvolume (float, optional) – The maximum tetrahedron volume. Defaults to -1.0 (no limit). This is only used for Volumetric Entity that requires tetraheralization.

  • verbose (int, optional) – The verbosity level during tetraheralization. Defaults to 0. This is only used for Volumetric Entity that requires tetraheralization.

  • force_retet (bool, optional) – Whether to force re-tetraheralization. Defaults to False. This is only used for Volumetric Entity that requires tetraheralization.