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)[source]#
Bases:
RBCRigidLink 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_pos(envs_idx=None)[source]#
Get the position of the link in the world frame.
- Parameters:
envs_idx (int or array of int, optional) – The indices of the environments to get the position. If None, get the position of all environments. Default is None.
- get_quat(envs_idx=None)[source]#
Get the quaternion of the link in the world frame.
- Parameters:
envs_idx (int or array of int, optional) – The indices of the environments to get the quaternion. If None, get the quaternion of all environments. Default is None.
- get_vel(envs_idx=None) Tensor[source]#
Get the linear velocity of the link in the world frame.
- Parameters:
envs_idx (int or array of int, optional) – The indices of the environments to get the linear velocity. If None, get the linear velocity of all environments. Default is None.
- get_ang(envs_idx=None) Tensor[source]#
Get the angular velocity of the link in the world frame.
- Parameters:
envs_idx (int or array of int, optional) – The indices of the environments to get the angular velocity. If None, get the angular velocity of all environments. Default is None.
- 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 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).
- get_vAABB(envs_idx=None)[source]#
Get the axis-aligned bounding box (AABB) of the link’s visual body in the world frame by aggregating all the visual geometries associated with this link (link.vgeoms).
- property uid#
The unique ID of the link.
- property name: str#
The name of the link.
- property entity: RigidEntity#
The entity that the link belongs to.
- property solver: RigidSolver#
The solver that the link belongs to.
- property visualize_contact: bool#
Whether to visualize the contact of the link.
- property joints: list['RigidJoint']#
The sequence of joints that connects the link to its parent link.
- property n_joints#
Number of the joints that connects the link to its parent link.
- property joint_start#
The start index of the link’s joints in the RigidSolver.
- property joint_end#
The end index of the link’s joints in the RigidSolver.
- property n_dofs#
The number of degrees of freedom (DOFs) of the entity.
- property dof_start#
The index of the link’s first degree of freedom (DOF) in the scene.
- property dof_end#
The index of the link’s last degree of freedom (DOF) in the scene plus one.
- property n_qs#
Returns the number of q variables of the link.
- property q_start#
Returns the starting index of the q variables of the link in the rigid solver.
- property q_end#
Returns the last index of the q variables of the link in the rigid solver plus one.
- property idx#
The global index of the link in the RigidSolver.
- property parent_idx#
The global index of the link’s parent link in the RigidSolver. If the link is the root link, return -1.
- property root_idx#
The global index of the link’s root link in the RigidSolver.
- property idx_local#
The local index of the link in the entity.
- property is_fixed#
Whether the link is fixed wrt the world.
- property invweight#
The invweight of the link.
- property pos: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str]#
The initial position of the link. For real-time position, use link.get_pos().
- property quat: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str]#
The initial quaternion of the link. For real-time quaternion, use link.get_quat().
- property inertial_pos: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] | None#
The initial position of the link’s inertial frame.
- property inertial_quat: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] | None#
The initial quaternion of the link’s inertial frame.
- property inertial_mass: float | None#
The initial mass of the link.
- property inertial_i: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] | 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 vgeoms: list[genesis.engine.entities.rigid_entity.rigid_geom.RigidVisGeom]#
The list of the link’s visualization geometries (RigidVisGeom).
- 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_vgeoms: int#
Number of the link’s visualization geometries (vgeom).
- property vgeom_start: int#
The start index of the link’s vgeom in the RigidSolver.
- property vgeom_end: int#
The end index of the link’s vgeom 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_vverts: int#
Number of vertices of all the link’s vgeoms.
- property n_faces: int#
Number of faces of all the link’s geoms.
- property n_vfaces: int#
Number of faces of all the link’s vgeoms.
- property n_edges: int#
Number of edges of all the link’s geoms.
- property is_built: bool#
Whether the entity the link belongs to is built.
- property is_free#