airobot.arm.yumi_palms_pybullet

Pybullet simulation environment of an ABB Yumi robot with Gelslim palms and a compliant wrist

class airobot.arm.yumi_palms_pybullet.CompliantYumiArm(cfgs, pb_client, seed=None, self_collision=False, eetool_cfg=None)[source]

Bases: airobot.arm.single_arm_pybullet.SingleArmPybullet

Class for the pybullet simulation of a single arm of the ABB Yumi robot, with additional joints specified to behave like springs.

Parameters:
  • cfgs (YACS CfgNode) – configurations for the arm.
  • pb_client (BulletClient) – pybullet client.
  • seed (int) – random seed.
  • self_collision (bool) – enable self_collision or not whiling loading URDF.
  • eetool_cfg (dict) – arguments to pass in the constructor of the end effector tool class.
Variables:
  • comp_jnt_names (list) – Names of the spring-like compliant joints.
  • comp_dof (list) – Number of spring-like compliant joints.
  • comp_jnt_gains (list) – Stiffness of spring-like compliant joints.
  • comp_jnt_ids (list) – PyBullet joint ids of compliant joints.
  • max_force_comp (list) – Maximum force that can be applied at the compliant joints.
set_compliant_jpos()[source]

Regulate compliant/spring like joints about nominal position.

set_jpos(position, joint_name=None, wait=True, ignore_physics=False, *args, **kwargs)[source]

Move the arm to the specified joint position(s). Applies regulation position command to the compliant joints after sending driven joint commands.

Parameters:
  • position (float or list) – desired joint position(s).
  • joint_name (str) – If not provided, position should be a list and all the actuated joints will be moved to the specified positions. If provided, only the specified joint will be moved to the desired joint position.
  • wait (bool) – whether to block the code and wait for the action to complete.
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits.

set_jtorq(torque, joint_name=None, wait=False, *args, **kwargs)[source]

Apply torque(s) to the joint(s), call enable_torque_control() or enable_torque_control(joint_name) before doing torque control. Applies regulation position command to the compliant joints after sending driven commands.

Note

call to this function is only effective in this simulation step. you need to supply torque value for each simulation step to do the torque control. It’s easier to use torque control in step_simulation mode instead of realtime_simulation mode. If you are using realtime_simulation mode, the time interval between two set_jtorq() calls must be small enough (like 0.0002s).

Parameters:
  • torque (float or list) – torque value(s) for the joint(s).
  • joint_name (str) – specify the joint on which the torque is applied. If it’s not provided(None), it will apply the torques on the six joints on the arm. Otherwise, only the specified joint will be applied with the given torque.
  • wait (bool) – Not used in this method, just to keep the method signature consistent.
Returns:

bool – Always return True as the torque will be applied as specified in Pybullet.

set_jvel(velocity, joint_name=None, wait=False, *args, **kwargs)[source]

Move the arm with the specified joint velocity(ies). Applies regulation position command to the compliant joints after sending driven commands.

Parameters:
  • velocity (float or list) – desired joint velocity(ies).
  • joint_name (str) – If not provided, velocity should be a list and all the actuated joints will be moved in the specified velocities. If provided, only the specified joint will be moved in the desired joint velocity.
  • wait (bool) – whether to block the code and wait for the action to complete.
Returns:

bool – A boolean variable representing if the action is successful at the moment when the function exits.

class airobot.arm.yumi_palms_pybullet.YumiPalmsPybullet(cfgs, pb_client, seed=None, self_collision=False, eetool_cfg=None)[source]

Bases: airobot.arm.dual_arm_pybullet.DualArmPybullet

Class for pybullet simulation of ABB Yumi robot with separate functionality for both arms, with two Gelslim Palms attached as end effectors instead of parallel jaw grippers.

Parameters:
  • cfgs (YACS CfgNode) – configurations for the arm.
  • pb_client (BulletClient) – pybullet client.
  • seed (int) – random seed.
  • self_collision (bool) – enable self_collision or not whiling loading URDF.
  • eetool_cfg (dict) – arguments to pass in the constructor of the end effector tool class.
Variables:
  • arms (dict) – internal dictioanry keyed by the single arm names, values are interfaces to the single arm instances.
  • robot_id (int) – pybullet unique body id of the robot.
  • left_arm (CompliantYumiArm) – left arm interface.
  • right_arm (CompliantYumiArm) – right arm interface.
reset(force_reset=False)[source]

Reset the simulation environment.

setup_single_arms(right_arm, left_arm)[source]

Function for setting up individual arms.

Parameters:
  • right_arm (CompliantYumiArm) – Instance of a single yumi arm with compliant joints.
  • left_arm (CompliantYumiArm) – Instance of a single yumi arm with compliant joints.