concepts.simulator.pybullet.components.robot_base.BulletMultiChainRobotRobotBase#
- class BulletMultiChainRobotRobotBase[source]#
Bases:
BulletRobotBaseBase class for humanoid robots, such as RBY1A, etc.
Methods
attach_object(ee_id, object_id, ee_to_object)create_gripper_constraint(ee_id, object_id)define_joint_groups(group_name, joint_indices)detach_object(ee_id)differential_ik(pos, quat, link_name_or_id, ...)Differential inverse kinematics.
do(action_name, *args, **kwargs)Execute an action primitive.
fk(qpos[, link_name_or_id])Forward kinematics.
get_attached_object(ee_id)Get the pybullet body ID of the robot.
Get the name of the robot body.
Get the pose of the robot body.
get_coriolis_torque([qpos, qvel])Get the Coriolis torque.
get_dof([group_name])Get the total degrees of freedom of the robot.
get_ee_default_quat([group_name])Get the default orientation of the end effector.
get_ee_link_default_quat(ee_link_id)get_ee_link_id([group_name])Get the pybullet link ID of the robot end effector.
get_ee_pose([group_name, fk])Get the pose of the end effector.
get_ee_quat_from_vectors([u, v, group_name])Compute the quaternion from two directions (the "down" direction for the end effector and the "forward" direction for the end effector).
get_ee_velocity([group_name, fk])Get the velocity of the end effector.
Get the home joint configuration.
get_jacobian([qpos, link_id, group_name])Get the Jacobian matrix.
get_joint_ids([group_name])Get the pybullet joint IDs of the robot.
get_joint_limits([group_name])Get the joint limits.
get_joint_names([group_name])Get the joint names of the robot.
get_link_index(name)get_link_pose(name_or_index)Get the pose of one of the links.
get_mass_matrix([qpos])Get the mass matrix.
get_qpos([group_name])Get the current joint configuration.
Get the current joint configuration.
get_qpos_nameddict([group_name])Get the current joint configuration.
get_qvel([group_name])Get the current joint velocity.
ik(pos, quat, link_name_or_id[, last_qpos, ...])Inverse kinematics.
ik_pybullet(pos, quat, link_id[, force, ...])ik_scipy(pos, quat, link_id[, last_qpos, ...])ik_tracik(pos, quat, link_id[, last_qpos, ...])ikfast(pos, quat, link_id[, last_qpos, ...])index_full_joint_state_by_name(state, names)index_full_joint_state_group(array, group_name)Index the full joint state to the group joint state.
is_qpos_valid(qpos)Check if the joint configuration is valid.
register_action_controller(name, func[, ...])Register an action primitive.
Reset the home joint configuration.
set_body_pose(pos, quat)Set the pose of the robot body.
set_ee_pose(pos, quat[, group_name])Set the pose of the end effector by inverse kinematics.
set_ik_method(ik_method)set_index_full_joint_state_by_name(state, ...)Set the group joint state to the full joint state.
set_qpos(qpos[, group_name, ...])Set the joint configuration.
set_qpos_groupdict(qpos_dict[, ...])Set the joint configuration.
set_qpos_nameddict(qpos_dict[, group_name, ...])Set the joint configuration.
Set the joint configuration with the gripper holding the object.
set_suppress_warnings([value])Attributes
Joint groups of the robot.
Joint names of each joint in the joint groups.
End effector link IDs of each joint groups.
Start index of each joint groups.
- __init__(client, body_name=None, gripper_objects=None, current_interface='pybullet', ik_method='pybullet', use_magic_gripper=True)[source]#
- __new__(**kwargs)#
- do(action_name, *args, **kwargs)#
Execute an action primitive.
- get_body_id()#
Get the pybullet body ID of the robot.
- Returns:
Body ID of the robot.
- Return type:
- get_body_pose()#
Get the pose of the robot body.
- Returns:
3D position and 4D quaternion of the robot body.
- Return type:
Tuple[np.ndarray, np.ndarray]
- get_ee_quat_from_vectors(u=(-1., 0., 0.), v=(1., 0., 0.), group_name=None)[source]#
Compute the quaternion from two directions (the “down” direction for the end effector and the “forward” direction for the end effector).
- get_link_pose(name_or_index)#
Get the pose of one of the links.
- get_mass_matrix(qpos=None)[source]#
Get the mass matrix.
- Parameters:
qpos (ndarray | None) – Joint configuration.
- Returns:
Mass matrix.
- Return type:
np.ndarray
- ik(pos, quat, link_name_or_id, last_qpos=None, force=False, max_distance=float('inf'), max_attempts=50, verbose=False)[source]#
Inverse kinematics.
- ik_scipy(pos, quat, link_id, last_qpos=None, max_distance=float('inf'), max_attempts=50, verbose=False)[source]#
- ik_tracik(pos, quat, link_id, last_qpos=None, max_distance=float('inf'), max_attempts=50, verbose=False)[source]#
- ikfast(pos, quat, link_id, last_qpos=None, max_attempts=50, max_distance=float('inf'), error_on_fail=True, verbose=False)[source]#
- index_full_joint_state_group(array, group_name)[source]#
Index the full joint state to the group joint state.
- register_action_controller(name, func, interface=None)#
Register an action primitive.
- Parameters:
- Raises:
ValueError – If the action primitive is already registered.
- Return type:
None
- reset_home_qpos()#
Reset the home joint configuration.
- set_body_pose(pos, quat)#
Set the pose of the robot body.
- set_ee_pose(pos, quat, group_name=None)[source]#
Set the pose of the end effector by inverse kinematics. Return True if the IK solver succeeds.
- set_index_full_joint_state_group_dict(full_array, group_values)[source]#
Set the group joint state to the full joint state.
- set_qpos(qpos, group_name='__all__', update_attached_objects=True)[source]#
Set the joint configuration.
- set_qpos_nameddict(qpos_dict, group_name='__all__', update_attached_objects=True)[source]#
Set the joint configuration.
- set_qpos_with_attached_objects(qpos)[source]#
Set the joint configuration with the gripper holding the object.
- Parameters:
qpos (ndarray) – Joint configuration.
- Return type:
None
- suppress_warnings()#
- joint_groups: Dict[str, Tuple[int, ...]]#
Joint groups of the robot. Each entry is represented as a tuple of joint indices in PyBullet.
- joint_groups_start_index: Dict[str, int | List[int]]#
Start index of each joint groups. This is the first joint index in a full qpos array (which contains only movable joints).
- property joint_name_to_state_index#
- property p#
- property w#
- property world#