RigidLink(刚体连杆)#
gs.RigidLink 是 Genesis 项目中的一个类,表示刚性链接。它继承自 RigidEntity 类,并包含以下成员:
- class genesis.engine.entities.rigid_entity.rigid_link.RigidLink(entity, name, idx, geom_start, cell_start, vert_start, face_start, edge_start, vgeom_start, vvert_start, vface_start, pos, quat, inertial_pos, inertial_quat, inertial_i, inertial_mass, parent_idx, invweight, visualize_contact)[源代码]#
基类:
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)[源代码]#
Get the position of the link in the world frame.
- 参数:
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)[源代码]#
Get the quaternion of the link in the world frame.
- 参数:
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)[源代码]#
Get the linear velocity of the link in the world frame.
- 参数:
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)[源代码]#
Get the angular velocity of the link in the world frame.
- 参数:
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()[源代码]#
Get the vertices of the link’s collision body (concatenation of all link.geoms) in the world frame.
- get_vverts()[源代码]#
Get the vertices of the link’s visualization body (concatenation of all link.vgeoms) in the world frame.
- get_AABB()[源代码]#
Get the axis-aligned bounding box (AABB) of the link’s collision body (concatenation of all link.geoms) in the world frame.
- get_vAABB()[源代码]#
Get the axis-aligned bounding box (AABB) of the link’s visual body (concatenation of all link.vgeoms) in the world frame.
- property uid#
The unique ID of the link.
- property name#
The name of the link.
- property entity#
The entity that the link belongs to.
- property solver#
The solver that the link belongs to.
- property visualize_contact#
Whether to visualize the contact of the link.
- property joint#
The joint that connects the link to its parent link.
- 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 child_idxs#
The global indices of the link’s child links in the RigidSolver.
- property idx_local#
The local index of the link in the entity.
- property parent_idx_local#
The local index of the link’s parent link in the entity. If the link is the root link, return -1.
- property child_idxs_local#
The local indices of the link’s child links in the entity.
- property is_leaf#
Whether the link is a leaf link (i.e., has no child links).
- property invweight#
The invweight of the link.
- property pos#
The initial position of the link. For real-time position, use link.get_pos().
- property quat#
The initial quaternion of the link. For real-time quaternion, use link.get_quat().
- property inertial_pos#
The initial position of the link’s inertial frame.
- property inertial_quat#
The initial quaternion of the link’s inertial frame.
- property inertial_mass#
The initial mass of the link.
- property inertial_i#
The inerial matrix of the link.
- property geoms#
The list of the link’s collision geometries (RigidGeom).
- property vgeoms#
The list of the link’s visualization geometries (RigidVisGeom).
- property n_geoms#
Number of the link’s collision geometries.
- property geom_start#
The start index of the link’s collision geometries in the RigidSolver.
- property geom_end#
The end index of the link’s collision geometries in the RigidSolver.
- property n_vgeoms#
Number of the link’s visualization geometries (vgeom).
- property vgeom_start#
The start index of the link’s vgeom in the RigidSolver.
- property vgeom_end#
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#
Number of vertices of all the link’s geoms.
- property n_vverts#
Number of vertices of all the link’s vgeoms.
- property n_faces#
Number of faces of all the link’s geoms.
- property n_vfaces#
Number of faces of all the link’s vgeoms.
- property n_edges#
Number of edges of all the link’s geoms.
- property is_built#
Whether the entity the link belongs to is built.