RigidEntity(刚体实体)#

gs.RigidEntity 是 Genesis 项目中的一个类,表示刚体实体。它包含了多个成员函数和属性,可以用于物理仿真和碰撞检测。

以下是 gs.RigidEntity 类的详细文档,包括所有成员函数和属性,以及继承关系和未记录的成员。

class genesis.engine.entities.rigid_entity.rigid_entity.RigidEntity(scene, solver, material, morph, surface, idx, idx_in_solver, link_start=0, joint_start=0, q_start=0, dof_start=0, geom_start=0, cell_start=0, vert_start=0, face_start=0, edge_start=0, vgeom_start=0, vvert_start=0, vface_start=0, visualize_contact=False)[源代码]#

基类:Entity

Entity class in rigid body systems. One rigid entity can be a robot, a terrain, a floating rigid body, etc.

get_jacobian(link)[源代码]#

Get the Jacobian matrix for a target link.

参数:

link (RigidLink) – The target link.

返回:

jacobian – The Jacobian matrix of shape (n_envs, 6, entity.n_dofs) or (6, entity.n_dofs) if n_envs == 0.

返回类型:

torch.Tensor

inverse_kinematics(link, pos=None, quat=None, init_qpos=None, respect_joint_limit=True, max_samples=50, max_solver_iters=20, damping=0.01, pos_tol=0.0005, rot_tol=0.005, pos_mask=[True, True, True], rot_mask=[True, True, True], max_step_size=0.5, return_error=False)[源代码]#

Compute inverse kinematics for a single target link.

参数:
  • link (RigidLink) – The link to be used as the end-effector.

  • pos (None | array_like, shape (3,), optional) – The target position. If None, position error will not be considered. Defaults to None.

  • quat (None | array_like, shape (4,), optional) – The target orientation. If None, orientation error will not be considered. Defaults to None.

  • init_qpos (None | array_like, shape (n_dofs,), optional) – Initial qpos used for solving IK. If None, the current qpos will be used. Defaults to None.

  • respect_joint_limit (bool, optional) – Whether to respect joint limits. Defaults to True.

  • max_samples (int, optional) – Number of resample attempts. Defaults to 50.

  • max_solver_iters (int, optional) – Maximum number of solver iterations per sample. Defaults to 20.

  • damping (float, optional) – Damping for damped least squares. Defaults to 0.01.

  • pos_tol (float, optional) – Position tolerance for normalized position error (in meter). Defaults to 1e-4.

  • rot_tol (float, optional) – Rotation tolerance for normalized rotation vector error (in radian). Defaults to 1e-4.

  • pos_mask (list, shape (3,), optional) – Mask for position error. Defaults to [True, True, True]. E.g.: If you only care about position along x and y, you can set it to [True, True, False].

  • rot_mask (list, shape (3,), optional) – Mask for rotation axis alignment. Defaults to [True, True, True]. E.g.: If you only want the link’s Z-axis to be aligned with the Z-axis in the given quat, you can set it to [False, False, True].

  • max_step_size (float, optional) – Maximum step size in q space for each IK solver step. Defaults to 0.5.

  • return_error (bool, optional) – Whether to return the final errorqpos. Defaults to False.

返回:

  • qpos (array_like, shape (n_dofs,) or (n_envs, n_dofs)) – Solver qpos (joint positions).

  • (optional) error_pose (array_like, shape (6,) or (n_envs, 6)) – Pose error for each target. The 6-vector is [err_pos_x, err_pos_y, err_pos_z, err_rot_x, err_rot_y, err_rot_z]. Only returned if return_error is True.

Compute inverse kinematics for multiple target links.

参数:
  • links (list of RigidLink) – List of links to be used as the end-effectors.

  • poss (list, optional) – List of target positions. If empty, position error will not be considered. Defaults to None.

  • quats (list, optional) – List of target orientations. If empty, orientation error will not be considered. Defaults to None.

  • init_qpos (array_like, shape (n_dofs,), optional) – Initial qpos used for solving IK. If None, the current qpos will be used. Defaults to None.

  • respect_joint_limit (bool, optional) – Whether to respect joint limits. Defaults to True.

  • max_samples (int, optional) – Number of resample attempts. Defaults to 50.

  • max_solver_iters (int, optional) – Maximum number of solver iterations per sample. Defaults to 20.

  • damping (float, optional) – Damping for damped least squares. Defaults to 0.01.

  • pos_tol (float, optional) – Position tolerance for normalized position error (in meter). Defaults to 1e-4.

  • rot_tol (float, optional) – Rotation tolerance for normalized rotation vector error (in radian). Defaults to 1e-4.

  • pos_mask (list, shape (3,), optional) – Mask for position error. Defaults to [True, True, True]. E.g.: If you only care about position along x and y, you can set it to [True, True, False].

  • rot_mask (list, shape (3,), optional) – Mask for rotation axis alignment. Defaults to [True, True, True]. E.g.: If you only want the link’s Z-axis to be aligned with the Z-axis in the given quat, you can set it to [False, False, True].

  • max_step_size (float, optional) – Maximum step size in q space for each IK solver step. Defaults to 0.5.

  • return_error (bool, optional) – Whether to return the final errorqpos. Defaults to False.

返回:

  • qpos (array_like, shape (n_dofs,) or (n_envs, n_dofs)) – Solver qpos (joint positions).

  • (optional) error_pose (array_like, shape (6,) or (n_envs, 6)) – Pose error for each target. The 6-vector is [err_pos_x, err_pos_y, err_pos_z, err_rot_x, err_rot_y, err_rot_z]. Only returned if return_error is True.

plan_path(qpos_goal, qpos_start=None, timeout=5.0, smooth_path=True, num_waypoints=100, ignore_collision=False, ignore_joint_limit=False, planner='RRTConnect')[源代码]#

Plan a path from qpos_start to qpos_goal.

参数:
  • qpos_goal (array_like) – The goal state.

  • qpos_start (None | array_like, optional) – The start state. If None, the current state of the rigid entity will be used. Defaults to None.

  • timeout (float, optional) – The maximum time (in seconds) allowed for the motion planning algorithm to find a solution. Defaults to 5.0.

  • smooth_path (bool, optional) – Whether to smooth the path after finding a solution. Defaults to True.

  • num_waypoints (int, optional) – The number of waypoints to interpolate the path. If None, no interpolation will be performed. Defaults to 100.

  • ignore_collision (bool, optional) – Whether to ignore collision checking during motion planning. Defaults to False.

  • ignore_joint_limit (bool, optional) – Whether to ignore joint limits during motion planning. Defaults to False.

  • planner (str, optional) – The name of the motion planning algorithm to use. Supported planners: ‘PRM’, ‘RRT’, ‘RRTConnect’, ‘RRTstar’, ‘EST’, ‘FMT’, ‘BITstar’, ‘ABITstar’. Defaults to ‘RRTConnect’.

返回:

waypoints – A list of waypoints representing the planned path. Each waypoint is an array storing the entity’s qpos of a single time step.

返回类型:

list

get_joint(name=None, id=None)[源代码]#

Get a RigidJoint object by name or id.

参数:
  • name (str, optional) – The name of the joint. Defaults to None.

  • id (str, optional) – The id of the joint. This can be a substring of the joint’s id. Defaults to None.

返回:

joint – The joint object.

返回类型:

RigidJoint

Get a RigidLink object by name or id.

参数:
  • name (str, optional) – The name of the link. Defaults to None.

  • id (str, optional) – The id of the link. This can be a substring of the link’s id. Defaults to None.

返回:

link – The link object.

返回类型:

RigidLink

get_pos(envs_idx=None)[源代码]#

Returns position of the entity’s base link.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

pos – The position of the entity’s base link.

返回类型:

torch.Tensor, shape (3,) or (n_envs, 3)

get_quat(envs_idx=None)[源代码]#

Returns quaternion of the entity’s base link.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

quat – The quaternion of the entity’s base link.

返回类型:

torch.Tensor, shape (4,) or (n_envs, 4)

get_vel(envs_idx=None)[源代码]#

Returns linear velocity of the entity’s base link.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

vel – The linear velocity of the entity’s base link.

返回类型:

torch.Tensor, shape (3,) or (n_envs, 3)

get_ang(envs_idx=None)[源代码]#

Returns angular velocity of the entity’s base link.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

ang – The angular velocity of the entity’s base link.

返回类型:

torch.Tensor, shape (3,) or (n_envs, 3)

Returns position of all the entity’s links.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

pos – The position of all the entity’s links.

返回类型:

torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)

Returns quaternion of all the entity’s links.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

quat – The quaternion of all the entity’s links.

返回类型:

torch.Tensor, shape (n_links, 4) or (n_envs, n_links, 4)

Returns linear velocity of all the entity’s links.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

vel – The linear velocity of all the entity’s links.

返回类型:

torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)

Returns angular velocity of all the entity’s links.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

ang – The angular velocity of all the entity’s links.

返回类型:

torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)

set_pos(pos, zero_velocity=True, envs_idx=None)[源代码]#

Set position of the entity’s base link.

参数:
  • pos (array_like) – The position to set.

  • zero_velocity (bool, optional) – Whether to zero the velocity of all the entity’s dofs. Defaults to True. This is a safety measure after a sudden change in entity pose.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

set_quat(quat, zero_velocity=True, envs_idx=None)[源代码]#

Set quaternion of the entity’s base link.

参数:
  • quat (array_like) – The quaternion to set.

  • zero_velocity (bool, optional) – Whether to zero the velocity of all the entity’s dofs. Defaults to True. This is a safety measure after a sudden change in entity pose.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

get_verts()[源代码]#

Get the all vertices of the entity (using collision geoms).

返回:

verts – The vertices of the entity (using collision geoms).

返回类型:

torch.Tensor, shape (n_verts, 3) or (n_envs, n_verts, 3)

get_AABB()[源代码]#

Get the axis-aligned bounding box (AABB) of the entity (using collision geoms).

返回:

AABB – The axis-aligned bounding box (AABB) of the entity (using collision geoms).

返回类型:

torch.Tensor, shape (2, 3) or (n_envs, 2, 3)

set_qpos(qpos, qs_idx_local=None, zero_velocity=True, envs_idx=None)[源代码]#

Set the entity’s qpos.

参数:
  • qpos (array_like) – The qpos to set.

  • qs_idx_local (None | array_like, optional) – The indices of the qpos to set. If None, all qpos will be set. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • zero_velocity (bool, optional) – Whether to zero the velocity of all the entity’s dofs. Defaults to True. This is a safety measure after a sudden change in entity pose.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

set_dofs_kp(kp, dofs_idx_local=None)[源代码]#

Set the entity’s dofs’ positional gains for the PD controller.

参数:
  • kp (array_like) – The positional gains to set.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to set. If None, all dofs will be set. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

set_dofs_kv(kv, dofs_idx_local=None)[源代码]#

Set the entity’s dofs’ velocity gains for the PD controller.

参数:
  • kv (array_like) – The velocity gains to set.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to set. If None, all dofs will be set. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

set_dofs_force_range(lower, upper, dofs_idx_local=None)[源代码]#

Set the entity’s dofs’ force range.

参数:
  • lower (array_like) – The lower bounds of the force range.

  • upper (array_like) – The upper bounds of the force range.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to set. If None, all dofs will be set. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

set_dofs_velocity(velocity, dofs_idx_local=None, envs_idx=None)[源代码]#

Set the entity’s dofs’ velocity.

参数:
  • velocity (array_like) – The velocity to set.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to set. If None, all dofs will be set. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

set_dofs_position(position, dofs_idx_local=None, zero_velocity=True, envs_idx=None)[源代码]#

Set the entity’s dofs’ position.

参数:
  • position (array_like) – The position to set.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to set. If None, all dofs will be set. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • zero_velocity (bool, optional) – Whether to zero the velocity of all the entity’s dofs. Defaults to True. This is a safety measure after a sudden change in entity pose.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

control_dofs_force(force, dofs_idx_local=None, envs_idx=None)[源代码]#

Control the entity’s dofs’ motor force. This is used for force/torque control.

参数:
  • force (array_like) – The force to apply.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to control. If None, all dofs will be controlled. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

control_dofs_velocity(velocity, dofs_idx_local=None, envs_idx=None)[源代码]#

Set the PD controller’s target velocity for the entity’s dofs. This is used for velocity control.

参数:
  • velocity (array_like) – The target velocity to set.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to control. If None, all dofs will be controlled. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

control_dofs_position(position, dofs_idx_local=None, envs_idx=None)[源代码]#

Set the PD controller’s target position for the entity’s dofs. This is used for position control.

参数:
  • position (array_like) – The target position to set.

  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to control. If None, all dofs will be controlled. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

get_qpos(qs_idx_local=None, envs_idx=None)[源代码]#

Get the entity’s qpos.

参数:
  • qs_idx_local (None | array_like, optional) – The indices of the qpos to get. If None, all qpos will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

qpos – The entity’s qpos.

返回类型:

torch.Tensor, shape (n_qs,) or (n_envs, n_qs)

get_dofs_control_force(dofs_idx_local=None, envs_idx=None)[源代码]#

Get the entity’s dofs’ internal control force, computed based on the position/velocity control command.

参数:
  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

control_force – The entity’s dofs’ internal control force.

返回类型:

torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)

get_dofs_force(dofs_idx_local=None, envs_idx=None)[源代码]#

Get the entity’s dofs’ internal force at the current time step.

备注

Different from get_dofs_control_force, this function returns the actual internal force experienced by all the dofs at the current time step.

参数:
  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

force – The entity’s dofs’ force.

返回类型:

torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)

get_dofs_velocity(dofs_idx_local=None, envs_idx=None)[源代码]#

Get the entity’s dofs’ velocity.

参数:
  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

velocity – The entity’s dofs’ velocity.

返回类型:

torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)

get_dofs_position(dofs_idx_local=None, envs_idx=None)[源代码]#

Get the entity’s dofs’ position.

参数:
  • dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

返回:

position – The entity’s dofs’ position.

返回类型:

torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)

get_dofs_kp(dofs_idx_local=None)[源代码]#

Get the positional gain (kp) for the entity’s dofs used by the PD controller.

参数:

dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

返回:

kp – The positional gain (kp) for the entity’s dofs.

返回类型:

torch.Tensor, shape (n_dofs,)

get_dofs_kv(dofs_idx_local=None)[源代码]#

Get the velocity gain (kv) for the entity’s dofs used by the PD controller.

参数:

dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

返回:

kv – The velocity gain (kv) for the entity’s dofs.

返回类型:

torch.Tensor, shape (n_dofs,)

get_dofs_force_range(dofs_idx_local=None)[源代码]#

Get the force range (min and max limits) for the entity’s dofs.

参数:

dofs_idx_local (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

返回:

  • lower_limit (torch.Tensor, shape (n_dofs,)) – The lower limit of the force range for the entity’s dofs.

  • upper_limit (torch.Tensor, shape (n_dofs,)) – The upper limit of the force range for the entity’s dofs.

get_dofs_limit(dofs_idx=None)[源代码]#

Get the positional limits (min and max) for the entity’s dofs.

参数:

dofs_idx (None | array_like, optional) – The indices of the dofs to get. If None, all dofs will be returned. Note that here this uses the local q_idx, not the scene-level one. Defaults to None.

返回:

  • lower_limit (torch.Tensor, shape (n_dofs,)) – The lower limit of the positional limits for the entity’s dofs.

  • upper_limit (torch.Tensor, shape (n_dofs,)) – The upper limit of the positional limits for the entity’s dofs.

zero_all_dofs_velocity(envs_idx=None)[源代码]#

Zero the velocity of all the entity’s dofs.

参数:

envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

detect_collision(env_idx=0)[源代码]#

Detects collision for the entity. This only supports a single environment.

备注

This function re-detects real-time collision for the entity, so it doesn’t rely on scene.step() and can be used for applications like motion planning, which doesn’t require physical simulation during state sampling.

参数:

env_idx (int, optional) – The index of the environment. Defaults to 0.

get_contacts(with_entity=None)[源代码]#

Returns contact information computed during the most recent scene.step(). If with_entity is provided, only returns contact information involving the caller entity and the specified with_entity. Otherwise, returns all contact information involving the caller entity.

The returned dict contains the following keys (a contact pair consists of two geoms: A and B):

  • ‘geom_a’ : The global geom index of geom A in the contact pair. (actual geom object can be obtained by scene.rigid_solver.geoms[geom_a])

  • ‘geom_b’ : The global geom index of geom B in the contact pair. (actual geom object can be obtained by scene.rigid_solver.geoms[geom_b])

  • ‘link_a’ : The global link index of link A (that contains geom A) in the contact pair. (actual link object can be obtained by scene.rigid_solver.links[link_a])

  • ‘link_b’ : The global link index of link B (that contains geom B) in the contact pair. (actual link object can be obtained by scene.rigid_solver.links[link_b])

  • ‘position’ : The contact position in world frame.

  • ‘force_a’ : The contact force applied to geom A.

  • ‘force_b’ : The contact force applied to geom B.

  • ‘valid_mask’ : (Only when scene is parallelized) A boolean mask indicating whether the contact information is valid.

The shape of each entry is (n_envs, n_contacts, …) for scene with parallel envs, and (n_contacts, …) for non-parallelized scene.

参数:

with_entity (RigidEntity, optional) – The entity to check contact with. Defaults to None.

返回:

contact_info – The contact information.

返回类型:

dict

Returns net force applied on each links due to direct external contacts.

返回:

entity_links_force – The net force applied on each links due to direct external contacts.

返回类型:

torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)

set_friction_ratio(friction_ratio, link_indices, envs_idx=None)[源代码]#

Set the friction ratio of the geoms of the specified links. :param friction_ratio: The friction ratio :type friction_ratio: torch.Tensor, shape (n_envs, n_links) :param link_indices: The indices of the links to set friction ratio. :type link_indices: array_like :param envs_idx: The indices of the environments. If None, all environments will be considered. Defaults to None. :type envs_idx: None | array_like, optional

set_friction(friction)[源代码]#

Set the friction coefficient of all the links (and in turn, geoms) of the rigid entity. Note that for a pair of geoms in contact, the actual friction coefficient is set to be max(geom_a.friction, geom_b.friction), so you need to set for both geoms.

备注

In actual simulation, friction will be computed using max(max(ga_info.friction, gb_info.friction), 1e-2); i.e. the minimum friction coefficient is 1e-2.

参数:

friction (float) – The friction coefficient to set.

get_mass()[源代码]#

Get the total mass of the entity in kg.

返回:

mass – The total mass of the entity in kg.

返回类型:

float

property visualize_contact#

Whether to visualize contact force.

property init_qpos#

The initial qpos of the entity.

property n_qs#

The number of q (generalized coordinates) of the entity.

The number of RigidLink in the entity.

property n_joints#

The number of RigidJoint in the entity.

property n_dofs#

The number of degrees of freedom (DOFs) of the entity.

property n_geoms#

The number of RigidGeom in the entity.

property n_cells#

The number of sdf cells in the entity.

property n_verts#

The number of vertices (from collision geom RigidGeom) in the entity.

property n_faces#

The number of faces (from collision geom RigidGeom) in the entity.

property n_edges#

The number of edges (from collision geom RigidGeom) in the entity.

property n_vgeoms#

The number of vgeoms (visual geoms - RigidVisGeom) in the entity.

property n_vverts#

The number of vverts (visual vertices, from vgeoms) in the entity.

property n_vfaces#

The number of vfaces (visual faces, from vgeoms) in the entity.

property geom_start#

The index of the entity’s first RigidGeom in the scene.

property geom_end#

The index of the entity’s last RigidGeom in the scene plus one.

property cell_start#

The start index the entity’s sdf cells in the scene.

property cell_end#

The end index the entity’s sdf cells in the scene plus one.

The index of the entity’s base link in the scene.

The index of the entity’s first RigidLink in the scene.

The index of the entity’s last RigidLink in the scene plus one.

property dof_start#

The index of the entity’s first degree of freedom (DOF) in the scene.

property gravity_compensation#

Apply a force to compensate gravity. A value of 1 will make a zero-gravity behavior. Default to 0

property dof_end#

The index of the entity’s last degree of freedom (DOF) in the scene plus one.

property vert_start#

The index of the entity’s first vert (collision vertex) in the scene.

property vvert_start#

The index of the entity’s first vvert (visual vertex) in the scene.

property face_start#

The index of the entity’s first face (collision face) in the scene.

property vface_start#

The index of the entity’s first vface (visual face) in the scene.

property edge_start#

The index of the entity’s first edge (collision edge) in the scene.

property q_start#

The index of the entity’s first q (generalized coordinates) in the scene.

property q_end#

The index of the entity’s last q (generalized coordinates) in the scene plus one.

property geoms#

The list of collision geoms (RigidGeom) in the entity.

property vgeoms#

The list of visual geoms (RigidVisGeom) in the entity.

The list of links (RigidLink) in the entity.

property joints#

The list of joints (RigidJoint) in the entity.

The base link of the entity

property base_joint#

The base joint of the entity