abb_motion_program_exec

ABB IRC5 Controller Motion Program command client.

This module contains types found on the ABB Robot Controller. Documentation is taken from the ABB Robotics manual “Technical reference manual RAPID Instructions, Functions and Data types, Document ID: 3HAC 16581-1”. Note that most of the following data structures are all direct copies of the underlying ABB types.

abb_motion_program_exec

class abb_motion_program_exec.CirPathModeSwitch(value)

ABB RAPID Options for CirPathMode command

CirPointOri = 3

Pass through ToPoint during MoveC

ObjectFrame = 2

Object Frame

PathFrame = 1

Path Frame

Wrist45 = 4

Wrist45

Wrist46 = 5

Wrist46

Wrist56 = 6

Wrist56

class abb_motion_program_exec.EGMJointTargetConfig(J1: egm_minmax, J2: egm_minmax, J3: egm_minmax, J4: egm_minmax, J5: egm_minmax, J6: egm_minmax, max_pos_deviation: float, max_speed_deviation: float)

Activate EGM for joint target control

J1: egm_minmax

J1 convergence criteria

J2: egm_minmax

J2 convergence criteria

J3: egm_minmax

J3 convergence criteria

J4: egm_minmax

J4 convergence criteria

J5: egm_minmax

J5 convergence criteria

J6: egm_minmax

J6 convergence criteria

max_pos_deviation: float

Max joint deviation in degrees

max_speed_deviation: float

Max joint speed deviation in degrees/second

class abb_motion_program_exec.EGMPathCorrectionConfig(sensor_frame: pose)

Activate EGM for path correction (EGMMoveL, EGMMoveC)

sensor_frame: pose

The sensor frame

class abb_motion_program_exec.EGMPoseTargetConfig(corr_frame: pose, corr_fr_type: egmframetype, sensor_frame: pose, sensor_fr_type: egmframetype, x: egm_minmax, y: egm_minmax, z: egm_minmax, rx: egm_minmax, ry: egm_minmax, rz: egm_minmax, max_pos_deviation: float, max_speed_deviation: float)

Activate EGM for pose target control

corr_fr_type: egmframetype

The correction frame type

corr_frame: pose

The correction frame

max_pos_deviation: float

Max joint deviation in degrees

max_speed_deviation: float

Max joint speed deviation in degrees/second

rx: egm_minmax

rx convergence criteria

ry: egm_minmax

ry convergence criteria

rz: egm_minmax

rz convergence criteria

sensor_fr_type: egmframetype

The sensor frame type

sensor_frame: pose

The sensor frame

x: egm_minmax

x convergence criteria

y: egm_minmax

y convergence criteria

z: egm_minmax

z convergence criteria

class abb_motion_program_exec.EGMStreamConfig

Configure EGM to stream feedback data only

class abb_motion_program_exec.MotionProgramExecClient(base_url='http://127.0.0.1:80', username='Default User', password='robotics', abb_client=None)

Client to execute motion programs an ABB IRC5 controller using Robot Web Services (RWS)

Variables:

abb_client – Instance of abb_robot_client.rws.RWS used execute commands

Parameters:
  • base_url – Base URL of the robot. For Robot Studio instances, this should be http://127.0.0.1:80, the default value. For a real robot, 127.0.0.1 should be replaced with the IP address of the robot controller. The WAN port ethernet must be used, not the maintenance port.

  • username – The HTTP username for the robot. Defaults to ‘Default User’

  • password – The HTTP password for the robot. Defaults to ‘robotics’

disable_motion_logging()

Disable motion logging

enable_motion_logging()

Enable motion logging

execute_motion_program(motion_program, task='T_ROB1', wait=True, seqno=None)

Execute a motion program. If wait is True, executes the following steps:

  1. Convert motion_program to bytes

  2. Upload binary motion program to controller as a temporary file on the controller ramdisk

  3. Check the last sequence number of the controller event log before starting the program

  4. Start executing the motion program by starting the RAPID task on the controller

  5. Wait for the RAPID task to complete

  6. Read the event log to check for errors, and find the filename of the saved joint log

  7. Read the joint log file from the controller

  8. Parse and return the joint log

If wait is set to False, the process stops after retrieving the most recent sequence number and returns that value.

Parameters:
  • motion_program (MotionProgram) – The motion program to execute

  • task (str) – The RAPID Task to use to execute the program. Defaults to T_ROB1

  • wait (bool) – If True, wait for the program to complete. Else, return once the program has been started.

  • seqno (Optional[int]) – Optional motion program seqno override

Return type:

Union[MotionProgramResultLog, int]

execute_multimove_motion_program(motion_programs, tasks=None, wait=True, seqno=None)

Execute a motion program on a MultiMove system with multiple robots. Same as MotionProgramExecClient.execute_motion_program() but takes lists of motion programs and tasks.

Motion programs should use SyncMoveOn() command when using MultiMove.

Parameters:
  • motion_programs (List[MotionProgram]) – A list of motion programs. Number of motion programs must correspond to number of robots.

  • tasks (Optional[List[str]]) – A list of RAPID Tasks. Defaults to T_ROBn, where n is the default task number for the robots.

  • wait (bool) – If True, wait for the program to complete. Else, return once the program has been started.

  • seqno (Optional[int]) – Optional motion program seqno override

get_current_cmdnum()

Get the currently executing cmdnum

Return type:

int

get_current_preempt_number()

Get the current preempt_number

Return type:

int

get_motion_logging_enabled()

Return if motion logging is enabled

Return type:

bool

get_queued_cmdnum()

Get the currently queued cmdnum. Motion commands are queued by the controller before executing, so the controller may queue up to three commands before executing them.

Return type:

int

is_motion_program_running()

Returns True if motion program is running

Return type:

bool

preempt_motion_program(motion_program, task='T_ROB1', preempt_number=1, preempt_cmdnum=-1, seqno=None)

Preempt a running motion program. Preempting works by downloading a replacement motion program file to the controller, and then switching to the new file at a specified command number. Multiple preemptions can occur on the same motion program, as long as each preempting has an increasing crossover command number.

Preempting can only occur after the currently queued command. The ABB controller will read ahead up to motion three motion commands. This means that there may be some delay before the preemption can occur.

Parameters:
  • motion_program (MotionProgram) – The new motion program. The first-cmd_num parameter of the motion program must be specified to be one greater than the preempt_cmdnum.

  • task (str) – The task to preempt

  • preempt_number (int) – The number of the preemption. The first preemption should set this to 1

  • preempt_cmdnum (int) – The command number to switch to the new motion program. Must be greater than the currently queued command number.

  • seqno (Optional[int]) – Optional override of the motion program seqno

preempt_multimove_motion_program(motion_programs, tasks=None, preempt_number=1, preempt_cmdnum=-1, seqno=None)

Preempt a motion program on a MultiMove system with multiple robots. Same as MotionProgramExecClient.preempt_motion_program() but takes lists of motion programs and tasks.

Parameters:
  • motion_program – List of new motion programs. The first-cmd_num parameter of the motion program must be specified to be one greater than the preempt_cmdnum.

  • task – The tasks to preempt

  • preempt_number (int) – The number of the preemption. The first preemption should set this to 1

  • preempt_cmdnum (int) – The command number to switch to the new motion program. Must be greater than the currently queued command number.

  • seqno (Optional[int]) – Optional override of the motion program seqno

read_motion_program_result_log(prev_seqnum)

Read a motion program result log after motion program completes. This function is called by MotionProgramExecClient.execute_motion_program() if wait is True. If wait is False, it can be called directly.

Parameters:

prev_seqnum (int) – The previous seqnum, returned by execute_motion_program() if wait is False.

Return type:

MotionProgramResultLog

Returns:

The result log

stop_egm()

Stop a long running EGM command. This will cause the program to complete normally

stop_motion_program()

Stop a motion program. Motion programs will normally stop when complete, so this is not normally necessary

wait_motion_program_complete()

Wait for motion program to complete

class abb_motion_program_exec.confdata(cf1: float, cf4: float, cf6: float, cfx: float)

ABB RAPID confdata structure. This structure has a very peculiar meaning. See the reference manual for details.

cf1: float

cf1

cf4: float

cf4

cf6: float

cf6

cfx: float

cfx

class abb_motion_program_exec.egm_minmax(min: float, max: float)

egm_minmax structure

max: float

max value

min: float

min value

class abb_motion_program_exec.egmframetype(value)

Frame types for corrections and sensor measurements

EGM_FRAME_BASE = 0

Base frame

EGM_FRAME_JOINT = 4

Joint frame

EGM_FRAME_TOOL = 1

Tool frame

EGM_FRAME_WOBJ = 2

Wobj frame

EGM_FRAME_WORLD = 3

World frame

class abb_motion_program_exec.jointtarget(robax: ndarray, extax: ndarray)

ABB RAPID jointtarget structure

extax: ndarray

The position of external axes. Must have 6 elements

robax: ndarray

Axis positions of the robot axes in degrees. Must have 6 elements

class abb_motion_program_exec.loaddata(mass: float, cog: ndarray, aom: ndarray, ix: float, iy: float, iz: float)

ABB RAPID loaddata structure

aom: ndarray

Axes of moment (principal axis) transform [w,x,y,z]

cog: ndarray

Center of gravity [x,y,z] in mm

ix: float

x-axis moment in kgm^2

iy: float

y-axis moment in kgm^2

iz: float

z-axis moment in kgm^2

mass: float

Mass in kg

class abb_motion_program_exec.pose(trans: ndarray, rot: ndarray)

ABB RAPID pose structure

rot: ndarray

Rotation in quaternions. [w,x,y,z] format

trans: ndarray

Translation in mm. Must have 3 elements

class abb_motion_program_exec.robtarget(trans: ndarray, rot: ndarray, robconf: confdata, extax: ndarray)

ABB RAPID robtarget structure

extax: ndarray

External axes positions. Must have 6 elements

robconf: confdata

Robot configuration

rot: ndarray

Rotation in quaternions. [w,x,y,z] format

trans: ndarray

Translation [x,y,z] in mm

class abb_motion_program_exec.speeddata(v_tcp: float, v_ori: float, v_leax: float, v_reax: float)

ABB RAPID speeddata structure.

The abb_motion_program_exec module contains constants for v5 through v5000 and vmax as found in RAPID.

v_leax: float

The velocity of linear external axes in mm/s.

v_ori: float

The reorientation velocity of the TCP expressed in degrees/s.

v_reax: float

The velocity of rotating external axes in degrees/s.

v_tcp: float

Velocity of the tool center point (TCP) in mm/s

class abb_motion_program_exec.tooldata(robhold: bool, tframe: pose, tload: loaddata)

ABB RAPID tooldata structure

robhold: bool

Defines whether or not the robot is holding the tool

tframe: pose

The tool coordinate system

tload: loaddata

The load of the tool

class abb_motion_program_exec.wobjdata(robhold: bool, ufprog: bool, ufmec: str, uframe: pose, oframe: pose)

ABB RAPID wobjdata structure

oframe: pose

Object coordinate system

robhold: bool

True if the robot is holding the work object. Typically False

ufmec: str

The mechanical unit which the robot movements are coordinated

ufprog: bool

Defines whether or not a fixed user coordinate system is used

uframe: pose

User coordinate system

class abb_motion_program_exec.zonedata(finep: bool, pzone_tcp: float, pzone_ori: float, pzone_eax: float, zone_ori: float, zone_leax: float, zone_reax: float)

ABB RAPID zonedata structure.

The abb_motion_program_exec module contains constants for fine and z0 through z200 as found in RAPID.

finep: bool

Defines whether the movement is to terminate as a stop point (fine point) or as a fly-by point.

pzone_eax: float

The zone size (the radius) for external axes.

pzone_ori: float

The zone size (the radius) for the tool reorientation.

pzone_tcp: float

The size (the radius) of the TCP zone in mm.

zone_leax: float

The zone size for linear external axes in mm.

zone_ori: float

The zone size for the tool reorientation in degrees.

zone_reax: float

The zone size for rotating external axes in degrees.

class abb_motion_program_exec.MotionProgram(first_cmd_num=1, tool=None, wobj=None, timestamp=None, egm_config=None, seqno=0, gripload=None)

Class representing a Motion Program. A Motion Program is a sequences of robot motion primitives that can be executed by the interpreter program running on the robot. This program must be installed before the motion program can be executed.

Motion commands are appended to the program by calling one of the motion program command functions. Currently supported commands are MoveAbsJ, MoveJ, MoveL, MoveC, WaitTime, CirPathMode, SyncMoveOn, SyncMoveOff, EGMRunJoint, EGMRunPose, EGMMoveL, and EGMMoveC

Parameters:
  • first_cmd_num (int) – The first command number for the motion program. Defaults to 1

  • tooldata – The tooldata to use for the motion program. Defaults to tool0

  • wobj (Optional[wobjdata]) – The wobjdata to use for the motion program. Defaults to wobj0

  • timestamp (Optional[str]) – The timestamp for the motion program. Defaults to current clock time

  • egm_config (Union[EGMStreamConfig, EGMJointTargetConfig, EGMPoseTargetConfig, EGMPathCorrectionConfig, None]) – The EGM configuration for the motion program. Can be used to activate feedback streaming, joint control, pose control, or path correction

  • seqno (int) – The sequence number of the command. Used by drivers commanding the robot

  • gripload (Optional[loaddata]) – The loaddata for the payload currently held by the robot

MoveAbsJ(to_joint_pos: jointtarget, speed: speeddata, zone: zonedata)

Append Move Absolute Joint command to motion program

Parameters:
  • to_joint_pos (jointtarget) – The destination absolute joint position of the robot and external axes.

  • speed (speeddata) – The speed data that applies to movements.

  • zone (zonedata) – Zone data for the movement.

MoveJ(to_point: robtarget, speed: speeddata, zone: zonedata)

Append move to position in joint space command to motion program

Parameters:
  • to_point (robtarget) – The destination point of the robot and external axes.

  • speed (speeddata) – The speed data that applies to movements.

  • zone (zonedata) – Zone data for the movement.

MoveL(to_point: robtarget, speed: speeddata, zone: zonedata)

Append move to position in straight line command to motion program

Parameters:
  • to_point (robtarget) – The destination point of the robot and external axes.

  • speed (speeddata) – The speed data that applies to movements.

  • zone (zonedata) – Zone data for the movement.

MoveC(cir_point: robtarget, to_point: robtarget, speed: speeddata, zone: zonedata)

Append move to position circularly through a point command to motion program

Parameters:
  • cir_point (robtarget) – The circle point of the robot and external axes.

  • to_point (robtarget) – The destination point of the robot and external axes.

  • speed (speeddata) – The speed data that applies to movements.

  • zone (zonedata) – Zone data for the movement.

WaitTime(t: float)

Append wait for a specified time in seconds command

Parameters:

t (float) – The time to wait in seconds

CirPathMode(switch: CirPathModeSwitch)

Append select reorientation method during circular moves command

Parameters:

switch (CirPathModeSwitch) – The selected circular reorientation method

SyncMoveOn()

Append enable synchronous move command. Only valid on MultiMove systems

SyncMoveOff()

Append disable synchronous move command. Only valid on MultiMove system

EGMRunJoint(cond_time: float, ramp_in_time: float, ramp_out_time: float)

Append run EGM joint target streaming motion command. Use MotionProgramExecClient.stop_egm() to exit EGM command mode.

Parameters:
  • cond_time (float) – Condition time for the move. Set to a very large number to continue running until stopped.

  • ramp_in_time – Motion ramp in time. Normally set to minimum value of 0.05

  • ramp_out_time – Motion ramp out time. Normally set to minimum value of 0.05

EGMRunPose(cond_time: float, ramp_in_time: float, ramp_out_time: float)

Apnned run EGM pose target streaming motion command. Use MotionProgramExecClient.stop_egm() to exit EGM command mode.

Parameters:
  • cond_time (float) – Condition time for the move. Set to a very large number to continue running until stopped.

  • ramp_in_time – Motion ramp in time. Normally set to minimum value of 0.05

  • ramp_out_time – Motion ramp out time. Normally set to minimum value of 0.05

  • offset (pose) – Offset of commanded pose. Typically set to zero offset and no rotation

EGMMoveL(to_point: robtarget, speed: speeddata, zone: zonedata)

Append move to position in straight line with EGM correction command to motion program

Parameters:
  • to_point (robtarget) – The destination point of the robot and external axes.

  • speed (speeddata) – The speed data that applies to movements.

  • zone (zonedata) – Zone data for the movement.

EGMMoveC(cir_point: robtarget, to_point: robtarget, speed: speeddata, zone: zonedata)

Append move to position circularly through a point with EGM correction command to motion program

Parameters:
  • cir_point (robtarget) – The circle point of the robot and external axes.

  • to_point (robtarget) – The destination point of the robot and external axes.

  • speed (speeddata) – The speed data that applies to movements.

  • zone (zonedata) – Zone data for the movement.

get_program_bytes(seqno=None)

Return binary motion program

Parameters:

seqno – The seqno of the program. Used by drivers, can be ignored for normal use

Return type:

bytes

get_program_rapid(module_name='motion_program_exec_gen', sync_move=False)

Returns equivalent RAPID program of the motion program. Useful for debugging motion programs.

Parameters:
  • module_name – The name of the RAPID module to write

  • sync_move – Set to True if the program is being used with a MulitMove synchronous program

Return type:

str

get_timestamp()

Get the timestamp of the motion program

Return type:

str

write_program(f, seqno=None)

Write binary motion program to binary file. The robot controller program will interpret the binary file to execute the motion program.

Parameters:
  • f (IOBase) – The target file to write program

  • seqno – The seqno of the program. Used by drivers, can be ignored for normal use

write_program_rapid(f, module_name='motion_program_exec_gen', sync_move=False)

Write equivalent RAPID program of the motion program. Useful for debugging motion programs.

Parameters:
  • f (TextIOBase) – The target file to write text RAPID program

  • module_name – The name of the RAPID module to write

  • sync_move – Set to True if the program is being used with a MulitMove synchronous program