RigidEntity#
- class genesis.engine.entities.rigid_entity.rigid_entity.RigidEntity(scene: Scene, solver: RigidSolver, material: Material, morph: Morph, surface: Surface, idx: int, idx_in_solver, link_start: int = 0, joint_start: int = 0, q_start=0, dof_start=0, geom_start=0, cell_start=0, vert_start=0, free_verts_state_start=0, fixed_verts_state_start=0, face_start=0, edge_start=0, vgeom_start=0, vvert_start=0, vface_start=0, custom_vvert_start=0, custom_vface_start=0, equality_start=0, visualize_contact: bool = False, morph_heterogeneous: list[genesis.options.morphs.Morph] | None = None, name: str | None = None)[source]#
Bases:
KinematicEntityPhysics-enabled rigid entity (collision, constraints, dynamics).
Inherits morphology, FK, IK, and DOF position get/set from KinematicEntity. Adds physics simulation methods: forces, velocities, contacts, etc.
- get_jacobian(link, local_point=None)[source]#
Get the spatial Jacobian for a point on a target link.
- Parameters:
link (RigidLink) – The target link.
local_point (torch.Tensor or None, shape (3,)) – Coordinates of the point in the link’s local frame. If None, the link origin is used (back-compat).
- Returns:
jacobian – The Jacobian matrix of shape (n_envs, 6, entity.n_dofs) or (6, entity.n_dofs) if n_envs == 0.
- Return type:
torch.Tensor
- inverse_kinematics(link, pos=None, quat=None, local_point=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, dofs_idx_local=None, return_error=False, envs_idx=None)[source]#
Compute inverse kinematics for a single target link.
- Parameters:
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.
local_point (None | array_like, shape (3,), optional) – A point in the link’s local frame to be positioned at pos. If None, the link origin is used. This is useful for positioning a tool center point (TCP) or fingertip that is offset from the link origin. Defaults to None (equivalent to [0, 0, 0]).
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.
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. This is used to specify which dofs the IK is applied to.
return_error (bool, optional) – Whether to return the final errorqpos. Defaults to False.
envs_idx (None | array_like, optional) – The indices of the environments to set. If None, all environments will be set. Defaults to None.
- Returns:
qpos (array_like, shape (n_dofs,) or (n_envs, n_dofs) or (len(envs_idx), n_dofs)) – Solver qpos (joint positions).
(optional) error_pose (array_like, shape (6,) or (n_envs, 6) or (len(envs_idx), 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.
- inverse_kinematics_multilink(links, poss=None, quats=None, local_points=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, dofs_idx_local=None, return_error=False, envs_idx=None)[source]#
Compute inverse kinematics for multiple target links.
- Parameters:
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.
local_points (list, optional) – List of local points (one per link) in each link’s local frame to be positioned at the corresponding target position. If empty or None, link origins are used. Each element should be array_like of shape (3,) or None. This is useful for positioning tool center points (TCP) or fingertips that are offset from the link origin. 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.
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. This is used to specify which dofs the IK is applied to.
return_error (bool, optional) – Whether to return the final errorqpos. Defaults to False.
envs_idx (None | array_like, optional) – The indices of the environments to set. If None, all environments will be set. Defaults to None.
- Returns:
qpos (array_like, shape (n_dofs,) or (n_envs, n_dofs) or (len(envs_idx), n_dofs)) – Solver qpos (joint positions).
(optional) error_pose (array_like, shape (6,) or (n_envs, 6) or (len(envs_idx), 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.
- forward_kinematics(qpos, qs_idx_local=None, links_idx_local=None, envs_idx=None)[source]#
Compute forward kinematics for a single target link.
- Parameters:
qpos (array_like, shape (n_qs,) or (n_envs, n_qs) or (len(envs_idx), n_qs)) – The joint positions.
qs_idx_local (None | array_like, optional) – The indices of the qpos to set. If None, all qpos will be set. Defaults to None.
links_idx_local (None | array_like, optional) – The indices of the links to get. If None, all links will be returned. Defaults to None.
envs_idx (None | array_like, optional) – The indices of the environments to set. If None, all environments will be set. Defaults to None.
- Returns:
links_pos (array_like, shape (n_links, 3) or (n_envs, n_links, 3) or (len(envs_idx), n_links, 3)) – The positions of the links (link frame origins).
links_quat (array_like, shape (n_links, 4) or (n_envs, n_links, 4) or (len(envs_idx), n_links, 4)) – The orientations of the links.
- plan_path(qpos_goal, qpos_start=None, max_nodes=2000, resolution=0.05, timeout=None, max_retry=1, smooth_path=True, num_waypoints=300, ignore_collision=False, planner='RRTConnect', envs_idx=None, return_valid_mask=False, *, ee_link_name=None, with_entity=None, **kwargs)[source]#
Plan a path from qpos_start to qpos_goal.
- Parameters:
qpos_goal (array_like) – The goal state. [B, Nq] or [1, Nq]
qpos_start (None | array_like, optional) – The start state. If None, the current state of the rigid entity will be used. Defaults to None. [B, Nq] or [1, Nq]
resolution (float, optiona) – Joint-space resolution. It corresponds to the maximum distance between states to be checked for validity along a path segment.
timeout (float, optional) – The max time to spend for each planning in seconds. Note that the timeout is not exact.
max_retry (float, optional) – Maximum number of retry in case of timeout or convergence failure. Default to 1.
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) – This option has been deprecated and is not longer doing anything.
planner (str, optional) – The name of the motion planning algorithm to use. Supported planners: ‘RRT’, ‘RRTConnect’. Defaults to ‘RRTConnect’.
envs_idx (None | array_like, optional) – The indices of the environments to set. If None, all environments will be set. Defaults to None.
return_valid_mask (bool) – Obtain valid mask of the succesful planed path over batch.
ee_link_name (str) – The name of the link, which we “attach” the object during the planning
with_entity (RigidEntity) – The (non-articulated) object to “attach” during the planning
- Returns:
path (torch.Tensor) – A tensor of waypoints representing the planned path. Each waypoint is an array storing the entity’s qpos of a single time step.
is_invalid (torch.Tensor) – A tensor of boolean mask indicating the batch indices with failed plan.
- get_AABB(envs_idx=None, *, allow_fast_approx: bool = False)[source]#
Get the axis-aligned bounding box (AABB) of the entity in world frame by aggregating all the collision geometries associated with this entity.
- Parameters:
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
allow_fast_approx (bool) – Whether to allow fast approximation for efficiency if supported, i.e. ‘LegacyCoupler’ is enabled. In this case, each collision geometry is approximated by their pre-computed AABB in geometry-local frame, which is more efficiency but inaccurate.
- Returns:
aabb – The AABB of the entity, where [:, 0] = min_corner (x_min, y_min, z_min) and [:, 1] = max_corner (x_max, y_max, z_max).
- Return type:
torch.Tensor, shape (2, 3) or (n_envs, 2, 3)
- get_links_pos(links_idx_local=None, envs_idx=None, *, ref: Literal['link_origin', 'link_com', 'root_com'] = 'link_origin')[source]#
Returns the position of a given reference point for all the entity’s links.
- Parameters:
links_idx_local (None | array_like) – The indices of the links. Defaults to None.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
ref ("link_origin" | "link_com" | "root_com") –
The reference point being used to express the position of each link. * “root_com”: center of mass of the sub-entities to which the link belongs. As a reminder, a single
kinematic tree (aka. ‘RigidEntity’) may compromise multiple “physical” entities, i.e. a kinematic tree that may have at most one free joint, at its root.
- Returns:
pos – The position of all the entity’s links.
- Return type:
torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)
- get_links_vel(links_idx_local=None, envs_idx=None, *, ref: Literal['link_origin', 'link_com'] = 'link_origin')[source]#
Returns linear velocity of all the entity’s links expressed at a given reference position in world coordinates.
- Parameters:
links_idx_local (None | array_like) – The indices of the links. Defaults to None.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
ref ("link_origin" | "link_com") – The reference point being used to expressed the velocity of each link.
- Returns:
vel – The linear velocity of all the entity’s links.
- Return type:
torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)
- set_pos(pos, envs_idx=None, *, zero_velocity=True, relative=False, skip_forward=False)[source]#
Set position of the entity’s base link.
- Parameters:
pos (array_like) – The position to set.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. 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.
relative (bool, optional) – Whether the position to set is absolute or relative to the initial (not current!) position. Defaults to False.
skip_forward (bool, optional) – Whether to skip forward kinematics after setting position. Defaults to False.
- set_quat(quat, envs_idx=None, *, zero_velocity=True, relative=False, skip_forward=False)[source]#
Set quaternion of the entity’s base link.
- Parameters:
quat (array_like) – The quaternion to set.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. 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.
relative (bool, optional) – Whether the quaternion to set is absolute or relative to the initial (not current!) quaternion. Defaults to False.
skip_forward (bool, optional) – Whether to skip forward kinematics after setting quaternion. Defaults to False.
- get_verts()[source]#
Get the all vertices of the entity based on collision geometries.
- Returns:
verts – The vertices of the entity.
- Return type:
torch.Tensor, shape (n_envs, n_verts, 3)
- set_qpos(qpos, qs_idx_local=None, envs_idx=None, *, zero_velocity=True, skip_forward=False)[source]#
Set the entity’s qpos.
- Parameters:
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.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. 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.
- set_dofs_kp(kp, dofs_idx_local=None, envs_idx=None)[source]#
Set the entity’s dofs’ positional gains for the PD controller.
- Parameters:
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.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- set_dofs_kv(kv, dofs_idx_local=None, envs_idx=None)[source]#
Set the entity’s dofs’ velocity gains for the PD controller.
- Parameters:
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.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- set_dofs_act_gain(act_gain, dofs_idx_local=None, envs_idx=None)[source]#
Set the actuator gain for the entity’s dofs. Invalidates PD-reducibility.
- Parameters:
act_gain (array_like) – The actuator gain values.
dofs_idx_local (None | array_like, optional) – The indices of the dofs. Defaults to None.
envs_idx (None | array_like, optional) – The indices of the environments. Defaults to None.
- set_dofs_act_bias(bias0, bias1, bias2, dofs_idx_local=None, envs_idx=None)[source]#
Set the actuator bias for the entity’s dofs.
- Parameters:
bias0 (array_like) – Constant bias term.
bias1 (array_like) – Position coefficient.
bias2 (array_like) – Velocity coefficient.
dofs_idx_local (None | array_like, optional) – The indices of the dofs. Defaults to None.
envs_idx (None | array_like, optional) – The indices of the environments. Defaults to None.
- set_dofs_force_range(lower, upper, dofs_idx_local=None, envs_idx=None)[source]#
Set the entity’s dofs’ force range.
- Parameters:
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.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- set_dofs_frictionloss(frictionloss, dofs_idx_local=None, envs_idx=None)[source]#
Set the entity’s dofs’ friction loss. :param frictionloss: The friction loss values to set. :type frictionloss: array_like :param dofs_idx_local: 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. :type dofs_idx_local: None | array_like, optional :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_dofs_position(position, dofs_idx_local=None, envs_idx=None, *, zero_velocity=True)[source]#
Set the entity’s dofs’ position.
- Parameters:
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.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. 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.
- control_dofs_force(force, dofs_idx_local=None, envs_idx=None)[source]#
Control the entity’s dofs’ motor force. This is used for force/torque control.
- Parameters:
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)[source]#
Set the PD controller’s target velocity for the entity’s dofs. This is used for velocity control.
- Parameters:
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)[source]#
Set the position controller’s target position for the entity’s dofs. The controller is a proportional term plus a velocity damping term (virtual friction).
- Parameters:
position (array_like) – The target position to set.
dofs_idx_local (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 (array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- control_dofs_position_velocity(position, velocity, dofs_idx_local=None, envs_idx=None)[source]#
Set a PD controller’s target position and velocity for the entity’s dofs. This is used for position control.
- Parameters:
position (array_like) – The target position to set.
velocity (array_like) – The target velocity
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_dofs_control_force(dofs_idx_local=None, envs_idx=None)[source]#
Get the entity’s dofs’ internal control force, computed based on the position/velocity control command.
- Parameters:
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.
- Returns:
control_force – The entity’s dofs’ internal control force.
- Return type:
torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)
- get_dofs_force(dofs_idx_local=None, envs_idx=None)[source]#
Get the entity’s dofs’ internal force at the current time step.
Note
Different from get_dofs_control_force, this function returns the actual internal force experienced by all the dofs at the current time step.
- Parameters:
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.
- Returns:
force – The entity’s dofs’ force.
- Return type:
torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)
- get_dofs_kp(dofs_idx_local=None, envs_idx=None)[source]#
Get the positional gain (kp) for the entity’s dofs used by the PD controller.
- Parameters:
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.
- Returns:
kp – The positional gain (kp) for the entity’s dofs.
- Return type:
torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)
- get_dofs_kv(dofs_idx_local=None, envs_idx=None)[source]#
Get the velocity gain (kv) for the entity’s dofs used by the PD controller.
- Parameters:
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.
- Returns:
kv – The velocity gain (kv) for the entity’s dofs.
- Return type:
torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)
- get_dofs_act_gain(dofs_idx_local=None, envs_idx=None)[source]#
Get the actuator gain for the entity’s dofs.
- Returns:
act_gain
- Return type:
torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)
- get_dofs_act_bias(dofs_idx_local=None, envs_idx=None)[source]#
Get the actuator bias [constant, pos_coeff, vel_coeff] for the entity’s dofs.
- Returns:
bias0, bias1, bias2
- Return type:
tuple of torch.Tensor
- get_dofs_force_range(dofs_idx_local=None, envs_idx=None)[source]#
Get the force range (min and max limits) for the entity’s dofs.
- Parameters:
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.
- Returns:
lower_limit (torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)) – The lower limit of the force range for the entity’s dofs.
upper_limit (torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)) – The upper limit of the force range for the entity’s dofs.
- get_dofs_frictionloss(dofs_idx_local=None, envs_idx=None)[source]#
Get the friction loss for the entity’s dofs.
- Parameters:
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.
- Returns:
frictionloss – The friction loss for the entity’s dofs.
- Return type:
torch.Tensor, shape (n_dofs,) or (n_envs, n_dofs)
- get_kinetic_energy(envs_idx=None) Tensor[source]#
Get the total kinetic energy of the entity in Joules [J] (translational + rotational).
Computed using the joint-space mass matrix:
KE = 0.5 * dq^T * M(q) * dq. The mass matrix is recomputed to include motor armature on the diagonal.Note
When the
approximate_implicitfastintegrator is used, this method forces recomputation of the mass matrix to exclude implicit damping terms added during integration. Other integrators do not require this recomputation.- Parameters:
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- Returns:
kinetic_energy
- Return type:
torch.Tensor, shape () or (n_envs,)
- get_potential_energy(envs_idx=None) Tensor[source]#
Get the total gravitational potential energy of the entity in Joules [J].
Computed as the sum over all links:
PE = sum_i(m_i * g^T * p_i), wherep_iis the center-of-mass position of link i andgis the gravity vector obtained from the solver.- Parameters:
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- Returns:
potential_energy
- Return type:
torch.Tensor, shape () or (n_envs,)
- get_total_energy(envs_idx=None) Tensor[source]#
Get the total mechanical energy of the entity in Joules [J] (kinetic + potential).
- Parameters:
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- Returns:
total_energy
- Return type:
torch.Tensor, shape () or (n_envs,)
- detect_collision(env_idx=0)[source]#
Detects collision for the entity. This only supports a single environment.
Note
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.
- Parameters:
env_idx (int, optional) – The index of the environment. Defaults to 0.
- get_contacts(with_entity=None, exclude_self_contact=False)[source]#
Returns contact information computed during the most recent scene.step(). If with_entity is provided, only returns contact information involving the caller and the specified entity. Otherwise, returns all contact information involving the caller entity. When with_entity is self, it will return the self-collision only.
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’A boolean mask indicating whether the contact information is valid.
(Only when scene is parallelized)
- The shape of each entry is (n_envs, n_contacts, …) for scene with parallel envs
and (n_contacts, …) for non-parallelized scene.
- Parameters:
with_entity (RigidEntity, optional) – The entity to check contact with. Defaults to None.
exclude_self_contact (bool) – Exclude the self collision from the returning contacts. Defaults to False.
- Returns:
contact_info – The contact information.
- Return type:
dict
- get_links_net_contact_force(envs_idx=None)[source]#
Returns net force applied on each links due to direct external contacts.
- Returns:
entity_links_force – The net force applied on each links due to direct external contacts.
- Return type:
torch.Tensor, shape (n_links, 3) or (n_envs, n_links, 3)
- set_friction_ratio(friction_ratio, links_idx_local=None, envs_idx=None)[source]#
Set the friction ratio of the geoms of the specified links.
- Parameters:
friction_ratio (torch.Tensor, shape (n_envs, n_links)) – The friction ratio
links_idx_local (array_like) – The indices of the links to set friction ratio.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- set_friction(friction)[source]#
Set the friction coefficient of all the links (and in turn, geometries) of the rigid entity.
Note
The friction coefficient associated with a pair of geometries in contact is defined as the maximum between their respective values, so one must be careful the set the friction coefficient properly for both of them.
Warning
The friction coefficient must be in range [1e-2, 5.0] for simulation stability.
- Parameters:
friction (float) – The friction coefficient to set.
- set_mass_shift(mass_shift, links_idx_local=None, envs_idx=None)[source]#
Set the mass shift of specified links.
- Parameters:
mass (torch.Tensor, shape (n_envs, n_links)) – The mass shift
links_idx_local (array_like) – The indices of the links to set mass shift.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- set_COM_shift(com_shift, links_idx_local=None, envs_idx=None)[source]#
Set the center of mass (COM) shift of specified links.
- Parameters:
com (torch.Tensor, shape (n_envs, n_links, 3)) – The COM shift
links_idx_local (array_like) – The indices of the links to set COM shift.
envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.
- get_mass()[source]#
Get the total mass of the entity in kg.
For heterogeneous entities, returns an array of masses for each environment. For non-heterogeneous entities, returns a scalar mass.
- Returns:
mass – The total mass of the entity in kg. For heterogeneous entities, returns an array of shape (n_envs,) with per-environment masses.
- Return type:
float | np.ndarray
- property visualize_contact#
Whether to visualize contact force.
- property n_geoms#
The number of collision geom 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 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.
- property gravity_compensation#
Apply a force to compensate gravity. A value of 1 will make a zero-gravity behavior. Default to 0
- property vert_start#
The index of the entity’s first vert (collision vertex) in the scene.
- property face_start#
The index of the entity’s first face (collision face) in the scene.
- property edge_start#
The index of the entity’s first edge (collision edge) in the scene.
- property geoms: list[genesis.engine.entities.rigid_entity.rigid_geom.RigidGeom]#
The list of collision geoms (RigidGeom) in the entity.
- property n_equalities#
The number of equality constraints in the entity.
- property equality_start#
The index of the entity’s first RigidEquality in the scene.
- property equality_end#
The index of the entity’s last RigidEquality in the scene plus one.
- property equalities#
The list of equality constraints (RigidEquality) in the entity.
- property is_free: bool#
- property is_local_collision_mask#
Whether the contype and conaffinity bitmasks of this entity only applies to self-collision.