RigidLink#
- class genesis.engine.entities.rigid_entity.rigid_link.RigidLink(entity: RigidEntity, name: str, idx: int, joint_start: int, n_joints: int, geom_start: int, cell_start: int, vert_start: int, face_start: int, edge_start: int, free_verts_state_start: int, fixed_verts_state_start: int, vgeom_start: int, vvert_start: int, vface_start: int, pos: np.typing.ArrayLike, quat: np.typing.ArrayLike, inertial_pos: np.typing.ArrayLike | None, inertial_quat: np.typing.ArrayLike | None, inertial_i: np.typing.ArrayLike | None, inertial_mass: float | None, parent_idx: int, root_idx: int | None, invweight: float | None, visualize_contact: bool, is_robot: bool)[source]#
Bases:
KinematicLinkRigidLink class. One RigidEntity consists of multiple RigidLinks, each of which is a rigid body and could consist of multiple RigidGeoms (link.geoms, for collision) and RigidVisGeoms (link.vgeoms for visualization).
- get_verts()[source]#
Get the vertices of the link’s collision body (concatenation of all link.geoms) in the world frame.
- get_AABB()[source]#
Get the vertex-based axis-aligned bounding box (AABB) of the link’s collision body in the world frame by aggregating all the collision geometries associated with this link (link.geoms).
- set_mass(mass: tuple[float, ...])[source]#
Set the mass of the link.
- Parameters:
mass (float | array_like, shape (n_envs,)) – The mass to set.
- property visualize_contact: bool#
Whether to visualize the contact of the link.
- property invweight#
The invweight of the link.
- property inertial_pos: ArrayLike | None#
The initial position of the link’s inertial frame.
- property inertial_quat: ArrayLike | None#
The initial quaternion of the link’s inertial frame.
- property inertial_mass: float | None#
The initial mass of the link.
- property inertial_i: ArrayLike | None#
The inerial matrix of the link.
- property geoms: list[genesis.engine.entities.rigid_entity.rigid_geom.RigidGeom]#
The list of the link’s collision geometries (RigidGeom).
- property n_geoms: int#
Number of the link’s collision geometries.
- property geom_start: int#
The start index of the link’s collision geometries in the RigidSolver.
- property geom_end: int#
The end index of the link’s collision geometries in the RigidSolver.
- property n_cells#
Number of sdf cells of all the link’s geoms.
- property n_verts: int#
Number of vertices of all the link’s geoms.
- property n_faces: int#
Number of faces of all the link’s geoms.
- property n_edges: int#
Number of edges of all the link’s geoms.
- property is_free#