gs.morphs.URDF#
gs.morphs.URDF 类是用于处理URDF文件的工具。URDF(统一机器人描述格式)是一种用于描述机器人模型的XML格式。这个类提供了一些方法来解析和操作URDF文件,以便在Genesis项目中使用。
- class genesis.options.morphs.URDF(*, pos: tuple = (0.0, 0.0, 0.0), euler: tuple | None = (0.0, 0.0, 0.0), quat: tuple | None = None, visualization: bool = True, collision: bool = True, requires_jac_and_IK: bool = True, file: Any = '', scale: float | tuple = 1.0, convexify: bool | None = None, recompute_inertia: bool = False, fixed: bool = False, prioritize_urdf_material: bool = False, merge_fixed_links: bool = True, links_to_keep: List[str] = [])[源代码]#
Morph loaded from a URDF file. This morph only supports RigidEntity. If you need to create a Drone entity, use gs.morphs.Drone instead.
备注
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.
- 参数:
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.
convexify (bool, optional) – Whether to convexify the entity. When convexify is True, all the meshes in the entity will be converted to a convex hull. If not given, it defaults to True for RigidEntity and False for other deformable entities.
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 [].