Controlling the Robot

YuMiState

class yumipy.YuMiState(vals=[0, 0, 0, 0, 0, 0, 0])

Object that encapsulates a yumi arm joint angle configuration.

YuMiArmFactory

class yumipy.YuMiArmFactory

Factory class for YuMiArm interfaces.

static YuMiArm(arm_type, name, ros_namespace=None)

Initializes a YuMiArm interface.

Parameters:
  • arm_type (string) –

    Type of arm. One of {‘local’, ‘remote’}

    ‘local’ creates a local YuMiArm object that communicates over ethernet

    ‘remote’ creates a YuMiArm object that communicates over ROS with a server

  • name (string) –

    Name of arm. One of {‘left’, ‘right’}.

    For local YuMiArm, the port kwarg is set to PORTS[{name}][“server”], where PORTS is defined in yumi_constants.py

    For remote YuMiArm, arm_service is set to ‘yumi_robot/{name}_arm’. This means that the namespace kwarg should be set to the namespace yumi_arms.launch was run in (or None if yumi_arms.launch was launched in the current namespace)

  • ros_namespace (string) – ROS namespace of arm. Used by remote YuMiArm only.

YuMiArm

class yumipy.YuMiArm(name, ip='192.168.125.1', port=5000, bufsize=4096, motion_timeout=8, comm_timeout=5, process_timeout=10, from_frame='tool', to_frame='base', debug=False, log_pose_histories=False, log_state_histories=False, motion_planner=None)

Interface to a single arm of an ABB YuMi robot. Communicates with the robot over Ethernet.

__init__(name, ip='192.168.125.1', port=5000, bufsize=4096, motion_timeout=8, comm_timeout=5, process_timeout=10, from_frame='tool', to_frame='base', debug=False, log_pose_histories=False, log_state_histories=False, motion_planner=None)

Initializes a YuMiArm interface. This interface will communicate with one arm (port) on the YuMi Robot. This uses a subprocess to handle non-blocking socket communication with the RAPID server.

Parameters:
  • name (string) – Name of the arm {‘left’, ‘right’}
  • ip (string formated ip address, optional) – IP of YuMi Robot. Default uses the one in YuMiConstants
  • port (int, optional) – Port of target arm’s server. Default uses the port for the left arm from YuMiConstants.
  • bufsize (int, optional) – Buffer size for ethernet responses
  • motion_timeout (float, optional) – Timeout for motion commands. Default from YuMiConstants.MOTION_TIMEOUT
  • comm_timeout (float, optional) – Timeout for non-motion ethernet communication. Default from YuMiConstants.COMM_TIMEOUT
  • process_timeout (float, optional) – Timeout for ethernet process communication. Default from YuMiConstants.PROCESS_TIMEOUT
  • from_frame (string, optional) – String name of robot arm frame. Default to “tool”
  • to_frame (string, optional) – String name of reference for robot frame Default to “base”
  • debug (bool, optional) – Boolean to indicate whether or not in debug mode. If in debug mode no ethernet communication is attempted. Mock responses will be returned. Default to YuMiConstants.DEBUG
  • log_pose_histories (bool, optional) – If True, uses yumi_history_logger to log pose histories. Enables usage of flush_pose_histories. Defaults to False
  • log_state_histories (bool, optional) – If True, uses yumi_history_logger to log state histories. Enables usage of flush_state_histories. Defaults to False
  • motion_planner (YuMiMotionPlanner, optional) – If given, will use for planning trajectories in joint space. Defaults to None
reset_settings()

Reset zone, tool, and speed settings to their last known values. This is used when reconnecting to the RAPID server after a server restart.

reset()

Resets the underlying yumi ethernet process and socket, and resets all the settings.

set_motion_planner(motion_planner)
Parameters:motion_planner (YuMiMotionPlanner) – Sets the current motion planner to the given motion planner.
flush_pose_histories(filename)
Parameters:filename (string) – Saves the pose history logger data to filename. Empties logger.
flush_state_histories(filename)
Parameters:filename (string) – Saves the state history logger data to filename. Empties logger
start()

Starts subprocess for ethernet communication.

stop()

Stops subprocess for ethernet communication. Allows program to exit gracefully.

ping(wait_for_res=True)

Pings the remote server.

Parameters:wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:out
Return type:Namedtuple (raw_res, data) from ping command.
Raises:YuMiCommException – If communication times out or socket error.
get_state(raw_res=False)

Get the current state (joint configuration) of this arm.

Parameters:raw_res (bool, optional) – If True, will return raw_res namedtuple instead of YuMiState Defaults to False
Returns:YuMiState if raw_res is False

_RES(raw_res, state) namedtuple if raw_res is True

Return type:out
Raises:YuMiCommException – If communication times out or socket error.
get_pose(raw_res=False)

Get the current pose of this arm to base frame of the arm.

Parameters:raw_res (bool, optional) – If True, will return raw_res namedtuple instead of YuMiState Defaults to False
Returns:RigidTransform if raw_res is False

_RES(raw_res, pose) namedtuple if raw_res is True

Return type:out
Raises:YuMiCommException – If communication times out or socket error.
is_pose_reachable(pose)

Check if a given pose is reachable (incurs no kinematic/joint-space limitations and self collisions)

Parameters:pose (RigidTransform) –
Returns:bool
Return type:True if pose is reachable, False otherwise.
Raises:YuMiCommException – If communication times out or socket error.
goto_state(state, wait_for_res=True)

Commands the YuMi to goto the given state (joint angles)

Parameters:
  • state (YuMiState) –
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) if state logging is not enabled and wait_for_res is False
  • { – ‘time’: <flaot>, ‘state’: <YuMistate>, ‘res’: <namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’)>
  • } otherwise. The time field indicates the duration it took for the arm to complete the motion.

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
goto_pose(pose, linear=True, relative=False, wait_for_res=True)

Commands the YuMi to goto the given pose

Parameters:
  • pose (RigidTransform) –
  • linear (bool, optional) – If True, will use MoveL in RAPID to ensure linear path. Otherwise use MoveJ in RAPID, which does not ensure linear path. Defaults to True
  • relative (bool, optional) – If True, will use goto_pose_relative by computing the delta pose from current pose to target pose. Defaults to False
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) if pose logging is not enabled and wait_for_res is False
  • { – ‘time’: <flaot>, ‘pose’: <RigidTransform>, ‘res’: <namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’)>
  • } otherwise. The time field indicates the duration it took for the arm to complete the motion.

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
goto_pose_linear_path(pose, wait_for_res=True, traj_len=10, eef_delta=0.01, jump_thresh=0.0)

Go to a pose via the shortest path in joint space

goto_pose_shortest_path(pose, wait_for_res=True, plan_timeout=0.1)

Go to a pose via the shortest path in joint space

goto_pose_delta(translation, rotation=None, wait_for_res=True)

Goto a target pose by transforming the current pose using the given translation and rotation

Parameters:
  • translation (list-like with length 3) – The translation vector (x, y, z) in meters.
  • rotation (list-like with length 3, optional) – The euler angles of given rotation in degrees. Defaults to 0 degrees - no rotation.
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
set_tool(pose, wait_for_res=True)

Sets the Tool Center Point (TCP) of the arm using the given pose.

Parameters:
  • pose (RigidTransform) –
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

set_speed(speed_data, wait_for_res=True)

Sets the target speed of the arm’s movements.

Parameters:
  • speed_data (list-like with length 4) – Specifies the speed data that will be used by RAPID when executing motions. Should be generated using YuMiRobot.get_v
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

set_zone(zone_data, wait_for_res=True)

Goto a target pose by transforming the current pose using the given translation and rotation

Parameters:
  • speed_data (list-like with length 4) – Specifies the speed data that will be used by RAPID when executing motions. Should be generated using YuMiRobot.get_v
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

move_circular(center_pose, target_pose, wait_for_res=True)

Goto a target pose by following a circular path around the center_pose

Parameters:
  • center_pose (RigidTransform) – Pose for the center of the circle for circula movement.
  • target_pose (RigidTransform) – Target pose
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
buffer_add_single(pose, wait_for_res=True)

Add single pose to the linear movement buffer in RAPID

Parameters:
  • pose (RigidTransform) –
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

buffer_add_all(pose_list, wait_for_res=True)

Add a list of poses to the linear movement buffer in RAPID

Parameters:
  • pose_list (list of RigidTransforms) –
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

buffer_clear(wait_for_res=True)

Clears the linear movement buffer in RAPID

Parameters:wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:
  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise
Raises:YuMiCommException – If communication times out or socket error.
buffer_size(raw_res=False)

Gets the current linear movement buffer size.

Parameters:wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:
  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise
Raises:YuMiCommException – If communication times out or socket error.
buffer_move(wait_for_res=True)

Executes the linear movement buffer

Parameters:wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:
  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise
Raises:YuMiCommException – If communication times out or socket error.
open_gripper(no_wait=False, wait_for_res=True)

Opens the gripper to the target_width

Parameters:

wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True

Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
close_gripper(force=20, width=0.0, no_wait=False, wait_for_res=True)

Closes the gripper as close to 0 as possible with maximum force.

Parameters:
  • force (float, optional) – Sets the corresponding gripping force in Newtons. Defaults to 20, which is the maximum grip force.
  • width (float, optional) – Sets the target width of gripper close motion in m. Cannot be greater than max gripper width. Defaults to 0.
  • no_wait (bool, optional) – If True, the RAPID server will continue without waiting for the gripper to reach its target width Defaults to True
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
move_gripper(width, no_wait=False, wait_for_res=True)

Moves the gripper to the given width in meters.

Parameters:
  • width (float) – Target width in meters
  • no_wait (bool, optional) – If True, the RAPID server will continue without waiting for the gripper to reach its target width Defaults to False
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
calibrate_gripper(max_speed=None, hold_force=None, phys_limit=None, wait_for_res=True)

Calibrates the gripper.

Parameters:
  • max_speed (float, optional) – Max speed of the gripper in mm/s. Defaults to None. If None, will use maximum speed in RAPID.
  • hold_force (float, optional) – Hold force used by the gripper in N. Defaults to None. If None, will use maximum force the gripper can provide (20N).
  • phys_limit (float, optional) – The maximum opening of the gripper. Defaults to None. If None, will use maximum opening the gripper can provide (25mm).
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

Notes

All 3 values must be provided, or they’ll all default to None.

set_gripper_force(force, wait_for_res=True)

Sets the gripper hold force

Parameters:
  • force (float) – Hold force by the gripper in N.
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

set_gripper_max_speed(max_speed, wait_for_res=True)

Sets the gripper max speed

Parameters:
  • max_speed (float) – In mm/s.
  • wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True
Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:

YuMiCommException – If communication times out or socket error.

get_gripper_width(raw_res=False)

Get width of current gripper in meters.

Parameters:

raw_res (bool, optional) –

Returns:

  • Width in meters if raw_res is False
  • namedtuple(‘_RES’, ‘res width’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
reset_home(wait_for_res=True)

Resets the arm to home using joints

Parameters:

wait_for_res (bool, optional) – If True, will block main process until response received from RAPID server. Defaults to True

Returns:

  • None if wait_for_res is False
  • namedtuple(‘_RAW_RES’, ‘mirror_code res_code message’) otherwise

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.

YuMiArm_ROS

class yumipy.YuMiArm_ROS(arm_service, namespace=None, timeout=10)

Interface to remotely control a single arm of an ABB YuMi robot. Communicates over ROS to a yumi arm server (initialize server through roslaunch)

Parameters:
  • arm_service (string) – ROSYumiArm service to interface with. If the ROSYumiArm services are started through yumi_arms.launch they will be called left_arm and right_arm
  • namespace (string, optional) – Namespace to prepend to arm_service. If None, current namespace is prepended.
__getattr__(name)

Override the __getattr__ method so that function calls become server requests

If the name is a method of the YuMiArm class, this returns a function that calls that function on the YuMiArm instance in the server. The wait_for_res argument is not available remotely and will always be set to True. This is to prevent odd desynchronized crashes

Otherwise, the name is considered to be an attribute, and getattr is called on the YuMiArm instance in the server. Note that if it isn’t an attribute either a RuntimeError will be raised.

The difference here is that functions access the server on call and non-functions do on getting the name

Also note that this is __getattr__, so things like __init__ and __dict__ WILL NOT trigger this function as the YuMiArm_ROS object already has these as attributes.

YuMiRobot

class yumipy.YuMiRobot(ip='192.168.125.1', port_l=5000, port_r=5001, tcp=RigidTransform(rotation=[[ 1. 0. 0.] [ 0. 1. 0.] [ 0. 0. 1.]], translation=[ 0. 0. 0.156], from_frame=unassigned, to_frame=world), include_left=True, include_right=True, debug=False, log_pose_histories=False, log_state_histories=False, arm_type='local', ros_namespace=None)

Interface to both arms of an ABB YuMi robot. Communicates with the robot over Ethernet.

__init__(ip='192.168.125.1', port_l=5000, port_r=5001, tcp=RigidTransform(rotation=[[ 1. 0. 0.] [ 0. 1. 0.] [ 0. 0. 1.]], translation=[ 0. 0. 0.156], from_frame=unassigned, to_frame=world), include_left=True, include_right=True, debug=False, log_pose_histories=False, log_state_histories=False, arm_type='local', ros_namespace=None)

Initializes a YuMiRobot

Parameters:
  • ip (string formatted IP Address, optional) – IP address of YuMi. Defaults to YuMiConstants.IP
  • port_l (int, optional) – Port of left arm server. Defaults to YuMiConstants.PORT_L
  • port_r (int, optional) – Port of right arm server. Defaults to YuMiConstants.PORT_R
  • tcp (RigidTransform, optional) – Tool Center Point Offset of the endeffectors. Defaults to YuMiConstants.TCP_DEFAULT_GRIPPER
  • include_left (bool, optional) – If True, the left arm is included and instantiated. Defaults to True
  • include_right (bool, optional) – If True, the right arm is included and instantiated. Defaults to True
  • debug (bool, optional) – If True, enables debug mode, so no ethernet socket will be created, and all response messages are faked. Defaults to YuMiConstants.DEBUG
  • log_pose_histories (bool, optional) – If True, uses yumi_history_logger to log pose histories. Enables usage of flush_pose_histories. Defaults to False
  • log_state_histories (bool, optional) – If True, uses yumi_history_logger to log state histories. Enables usage of flush_state_histories. Defaults to False
  • ros_namespace (string) – ROS namespace of arm. Used by remote YuMiArm only. If None, namespace is same as current ROS namespace
  • arm_type (string) –

    Type of arm. One of {‘local’, ‘remote’}

    ‘local’ creates local YuMiArm objects that communicates over ethernet. This ignores ros_namespace

    ‘remote’ creates YuMiArm objects that communicates over ROS with a server. This ignores ip, port_l, and port_r

Raises:

YuMiCommException – If communication times out or socket error.

reset()

Calls the reset function for each instantiated arm object.

start()

Calls the start function for each instantiated arm object.

stop()

Calls the stop function for each instantiated arm object.

open_grippers()

Calls open_gripper function for each instantiated arm object.

goto_state_sync(left_state, right_state)

Commands both arms to go to assigned states in sync. Sync means both motions will end at the same time.

Parameters:
  • left_state (YuMiState) – Target state for left arm
  • right_state (YuMiState) – Target state for right arm
Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
goto_pose_sync(left_pose, right_pose)

Commands both arms to go to assigned poses in sync. Sync means both motions will end at the same time.

Parameters:
  • left_pose (RigidTransform) – Target pose for left arm
  • right_pose (RigidTransform) – Target pose for right arm
Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
set_v(n)

Sets speed for both arms using n as the speed number.

Parameters:n (int) – speed number. If n = 100, then speed will be set to the corresponding v100 specified in RAPID. Loosely, n is translational speed in milimeters per second
Raises:YuMiCommException – If communication times out or socket error.
set_z(name)

Sets zoning settings for both arms according to name.

Parameters:name (str) – Name of zone setting. ie: “z10”, “z200”, “fine”
Raises:YuMiCommException – If communication times out or socket error.
set_tool(pose)

Sets TCP (Tool Center Point) for both arms using given pose as offset

Parameters:pose (RigidTransform) – Pose of new TCP as offset from the default TCP
Raises:YuMiCommException – If communication times out or socket error.
reset_home()

Moves both arms to home position

Raises:
  • YuMiCommException – If communication times out or socket error.
  • YuMiControlException – If commanded pose triggers any motion errors that are catchable by RAPID sever.
calibrate_grippers()

Calibrates grippers for instantiated arms.

Raises:YuMiCommException – If communication times out or socket error.
static construct_speed_data(tra, rot)

Constructs a speed data tuple that’s in the same format as ones used in RAPID.

Parameters:
  • tra (float) – translational speed (milimeters per second)
  • rot (float) – rotational speed (degrees per second)
Returns:

(tra, rot, tra, rot)

Return type:

A tuple of correctly formatted speed data

static get_v(n)

Gets the corresponding speed data for n as the speed number.

Parameters:n (int) – speed number. If n = 100, will return the same speed data as v100 in RAPID
Returns:
Return type:Corresponding speed data tuple using n as speed number
static get_z(name)

Gets the corresponding speed data for n as the speed number.

Parameters:name (str) – Name of zone setting. ie: “z10”, “z200”, “fine”
Returns:
Return type:Corresponding zone data dict to be used in set_z
static construct_zone_data(pzone_tcp, pzone_ori, zone_ori)

Constructs tuple for zone data

Parameters:
  • pzone_tcp (float) – path zone size for TCP
  • pzone_ori (float) – path zone size for orientation
  • zone_ori (float) – zone size for orientation
Returns:

(pzone_tcp, pzone_ori, zone_ori)

Return type:

A tuple of correctly formatted zone data