Inverse Kinematics API

Robot inverse kinematics is one of the core functions in industrial robot control systems, capable of converting position and orientation information in Cartesian space to angle information in robot joint space. Major robot manufacturers provide corresponding inverse kinematics API functions in their controllers to help users achieve precise motion control and path planning. The main function of inverse kinematics APIs is to calculate joint angles required for robot joints based on specified Tool Center Point (TCP) positions and orientations.

ABB

ABB robot controllers provide the CalcJointT function for inverse kinematics calculations. This function calculates joint angles for robot arm axes and external axes from specified robtarget data.

CalcJointT Function:

The CalcJointT (Calculate Joint Target) function can calculate joint angles for all robot axes based on specified robtarget data. During calculations, the function must consider specifications for Tool, WObj, and other related parameters. Input robtarget data should be specified using the same coordinate system during effective program displacement (ProgDisp) and external axis offset (EOffs) execution. After calculation completion, returned jointtarget data is expressed in calibration coordinate systems.

In MultiMove application types with coordinated workpieces in coordinated or synchronized coordinated modes, the CalcJointT function should not be used in specific situations when workpieces are moved by mechanical units in other program tasks. These situations include: calculating current positions of coordinated workpieces moved by robot arm units in current user coordinate systems, mechanical units in other program tasks remaining stationary, and using the \UseCurWObjPos parameter.

The function return value is jointtarget data type, containing angles for robot arm axes on the arm side (in degrees) and values for external axes (linear axes in mm, rotational axes in degrees). Return values are always related to calibration positions.

CalcJointT function syntax:

CalcJointT ([\UseCurWObjPos] Rob_target Tool [\WObj] [\ErrorNumber])
Parameter Name Data Type Description

[\UseCurWObjPos]

switch

Optional parameter for using current positions of coordinated workpieces moved by mechanical units in other tasks for calculation (current user coordinate system), obtaining all other data from RAPID programs

Rob_target

robtarget

Robot arm and external axis positions in outermost coordinate system related to specified tools and workpieces during effective program displacement (ProgDisp) and external axis offset (EOffs) execution

Tool

tooldata

Tool used for calculating robot arm joint angles

[\WObj]

wobjdata

Workpiece (coordinate system) related to robot arm position. If this parameter is omitted, workpiece wobj0 is used. This parameter must be specified when using stationary tools, coordinated external axes, or conveyor belts

[\ErrorNumber]

errnum

Used for error handling. If at least one axis is outside joint limit area or if limits to at least one coupling joint are exceeded, saves error number ERR_ROBLIMIT variable; if position (robtarget) is outside robot workspace, saves ERR_OUTSIDE_REACH

Program Execution:

Based on input Robtarget, returned jointtarget is calculated. If parameter \UseCurWObjPos is used, positions used come from current positions of mechanical units controlling user coordinate systems. To calculate robot arm joint angles, selected Tool, WObj (including coordinated user coordinate systems), and effective ProgDisp during execution should be considered. To calculate external axis positions during execution, effective tool EOffs should be considered.

Calculations always select robot arm configurations based on specified configuration data in input robtarget data. Commands ConfL and ConfJ do not affect this calculation principle. When using wrist singularities, robot arm axis 4 is set to 0 degrees.

If any effective program displacement (ProgDisp) and/or external axis offset (BOEEs) exist when robot positions are stored, the same program displacement and/or external axis offset must be effective during CalcJointT execution.

Limitations:

If coordinated coordinate systems are used, coordinated units must be possessed when using CalcJointT.

During CalcJointT execution, when TCP and coordination-related positions are involved, mechanical units controlling workpiece user coordinate systems must usually be ensured to be available.

CalcJointT typically uses robtarget, tooldata, and wobjdata from RAPID programs to calculate jointtarget. For coordinated workpieces, mechanical unit positions are used as external axis positions in robtarget, except when mechanical units are controlled by other program tasks (MultiMove systems) or mechanical units are not controlled by control systems (conveyor belts). For MultiMove systems except conveyor belts, parameter \UseCurwObjPos can be used if mechanical units remain stationary during CalcJointT execution.

Error Handling and Practical Examples

The system generates the following recoverable errors, handled in error handlers. System variable ERRNO will be set to the following values:

Error Code Error Cause

ERR_ROBLIMIT

Position is reachable, but at least one axis is outside joint limits or exceeds limits to at least one coupling joint

ERR_OUTSIDE_REACH

Position (robtarget) is outside robot workspace

ERR_WOBJ_MOVING

Mechanical unit controlling workpiece (user coordinate system) is not stationary during CalcJointT \UseCurWObjPos execution time

Basic Error Handling Example:

VAR errnum reach_error;
VAR jointtarget result_joints;

result_joints := CalcJointT(target_point, tool0 \WObj:=wobj0 \ErrorNumber:=reach_error);

IF reach_error = ERR_ROBLIMIT OR reach_error = ERR_OUTSIDE_REACH OR reach_error = ERR_WOBJ_MOVING THEN
    TPWrite "Position unreachable: " + NumToStr(reach_error, 0);
    ! Handle error situation - log error or request new target position
ELSE
    ! Execute normal motion
    MoveAbsJ result_joints, v1000, fine, tool0;
ENDIF

Reachability Check Example:

FUNC bool CanRobReach(robtarget ToPoint, PERS tooldata Tool, \PERS wobjdata WObj)
    VAR jointtarget jdump;
    jdump := CalcJointT(ToPoint, Tool \WObj?WObj);
    RETURN TRUE;
ERROR
    RETURN FALSE;
ENDFUNC

FANUC

FANUC robot controllers provide the POS2JOINT built-in function for inverse kinematics calculations. This routine converts Cartesian positions (in_pos) to joint angles (out_jnt) by calling inverse kinematics routines.

POS2JOINT function syntax:

POS2JOINT(ref_jnt, in_pos, uframe, utool, config_ref, wjnt_cfg, ext_ang, out_jnt, and status)

This function belongs to the MOTN environment group of %ENVIRONMENT Group.

Parameter Name Data Type Input/Output Description

ref_jnt

JOINTPOS

[in]

Reference joint position

in_pos

POSITION

[in]

Input Cartesian position

uframe

POSITION

[in]

User coordinate system

utool

POSITION

[in]

User tool coordinate system

config_ref

INTEGER

[in]

Configuration reference

wjnt_cfg

CONFIG

[in]

Wrist joint configuration

ext_ang

ARRAY OF REAL

[in]

External axis angle array

out_jnt

JOINTPOS

[out]

Output joint position

status

INTEGER

[out]

Execution status

YASKAWA

YASKAWA robot controllers provide the mpConvCartPosToAxes function to convert specified control group Cartesian coordinate positions (robot coordinate system) to angular positions.

mpConvCartPosToAxes function syntax:

int mpConvCartPosToAxes(
    unsigned int grp_no,
    MP_COORD* coord,
    unsigned int tool_no,
    BITSTRING fig_ctrl,
    long prev_angle[MP_GRP_AXES_NUM],
    MP_KINEMA_TYPE type,
    long angle[MP_GRP_AXES_NUM]
);
Parameter Name Data Type Description

grp_no

unsigned int

Control group number

coord

MP_COORD*

Cartesian coordinate position pointer

tool_no

unsigned int

Tool number

fig_ctrl

BITSTRING

Configuration control parameter

prev_angle

long[MP_GRP_AXES_NUM]

Previous angular position array

type

MP_KINEMA_TYPE

Kinematics type

angle

long[MP_GRP_AXES_NUM]

Output angular position array

KUKA

KUKA robot controllers provide the Inverse function for inverse kinematics calculations. This function calculates suitable robot axis angles from Cartesian positions with additional axis angles. Status and turn values do not need to be specified for Cartesian positions.

The Inverse function can be used to calculate resulting points when approaching in PTP with fine blocks. This function can check turn value validity and adjust at target points when needed.

Inverse function syntax:

result = INVERSE(position, start_axis, err_status)
Parameter Name Type Transfer Method Description

result

E6AXIS

Return value

Axis angles at transferred position

position

E6POS

IN parameter

Cartesian position based on base coordinate system (with additional axis angles if necessary), for which robot axis angles are calculated

start_axis

E6AXIS

IN parameter

Robot axis angles at motion starting point

err_status

INT

OUT parameter

Sets whether transferred axis angles (start_axis) should be checked at software limit switches

Using Starting Point start_axis

Starting point start_axis is needed in the following situations:

  • Target point has no status values. Status values that target points should obtain are defined through system variable $TARGET_STATUS:

Status Setting Description

$TARGET_STATUS=#SOURCE

Target point will obtain same status as starting point, status calculated from start_axis axis angles

$TARGET_STATUS=#BEST

Target point will obtain status where robot must travel as short as possible in axis space from starting point to target point

  • Target point has no turn values. Allowed turn values are calculated for specific axes, through which target points can have shortest paths to starting points. Here, turn values are allowed to exceed software limit switches.

  • Target point is near singularities. Axis angles must be determined and calculated for larger values. Angles that target points should maintain are set through system variable $SINGUL_POS[1…​3]:

Setting Value Description

$SINGUL_POS[1…​3]=0

Axis angles are determined as 0 degrees

$SINGUL_POS[1…​3]=1

Angles remain unchanged from starting point to target point

Error Handling and Practical Examples

Variable err_status transmits calculation results. If calculations are unsuccessful, this variable transmits values corresponding to error codes:

Value Description

-4

Preset variable $TOOL invalid

-3

Preset variable $BASE invalid

-2

err_status does not yet have valid values

-1

Not all main position variable components are defined, S and T need not be defined

0

Calculation successful, no errors

1

For specified axis angles, software limit switches are exceeded

2

No axis angles can reach Cartesian target positions

3

Although there are axis angles that can reach Cartesian target positions, specified turn values will exceed software limit switches

KUKA Inverse Kinematics Calculation Example:

DEF safe_inverse_calculation()
  DECL E6POS target_pos
  DECL E6AXIS start_joints, result_joints
  DECL INT error_status

  target_pos = {X 100.0, Y 200.0, Z 300.0, A 0.0, B 90.0, C 0.0}
  start_joints = $AXIS_ACT

  result_joints = INVERSE(target_pos, start_joints, error_status)

  SWITCH error_status
    CASE 0
      ; Calculation successful, execute motion
      PTP result_joints
    CASE 1, 2, 3
      ; Position unreachable or exceeds limits
      $MSG_T = {MSG_T: "Position unreachable, error code: " [] error_status []}
    DEFAULT
      ; Other errors
      $MSG_T = {MSG_T: "Calculation error: " [] error_status []}
  ENDSWITCH
END

ROKAE

ROKAE robot controllers provide the CalcJointT function to calculate corresponding joint angles based on specified robtarget variables. This function returns joint angles and external axis positions corresponding to input positions. Joint angle units are degrees, linear external axis units are millimeters (mm), and rotational external axis units are degrees.

This function is defined as:

CalcJointT(Rob_Target, Tool, Wobj)
Parameter Name Data Type Description

Rob_Target

robtarget

Specified Cartesian space target point. Note that tools and workpieces used during point definition should be consistent with tools/workpieces used in CalcJointT commands, otherwise incorrect results may occur

Tool

tool

Tool used for calculating joint angles. Note consistency with tools used when defining robtarget

Wobj

wobj

Workpiece coordinate system

UR

Universal Robot controllers provide the get_inverse_kin function to calculate inverse kinematic transformations (tool space to joint space). If qnear is defined, the solution closest to qnear will be returned. Otherwise, the solution closest to current joint positions is returned. If no tcp is provided, the controller’s currently active tcp will be used.

Parameter Name Type Description

x

tool pose

Tool pose

qnear

list of joint positions

Joint position list (optional)

maxPositionError

numeric

Maximum allowed position error (optional)

maxOrientationError

numeric

Maximum allowed orientation error (optional)

tcp

tcp offset pose

TCP offset pose (optional)

Function return value is joint positions. Example command:

get_inverse_kin(p[.1,.2,.2,0,3.14,0], [0.,3.14,1.57,.785,0,0])

Example parameters: x = p[.1, .2, .2, 0, 3.14, 0] represents pose with position x=100mm, y=200mm, z=200mm, and rotation vector rx=0 degrees, ry=180 degrees, rz=0 degrees. qnear = [0., 3.14, 1.57, .785, 0, 0] means solution should be close to joint angles j0=0 degrees, j1=180 degrees, j2=90 degrees, j3=45 degrees, j4=0 degrees, j5=0 degrees. maxPositionError defaults to 1e-10 meters, maxOrientationError defaults to 1e-10 radians.

PEITIAN

PEITIAN robot controllers also provide corresponding inverse kinematics calculation functions. Its frame structure type contains complete descriptions of position and orientation information.

Member Name Data Type Description

x

double

X component of transformed coordinate system origin coordinates in original coordinate system, unit millimeters

y

double

Y component of transformed coordinate system origin coordinates in original coordinate system, unit millimeters

z

double

Z component of transformed coordinate system origin coordinates in original coordinate system, unit millimeters

a

double

A component of transformed coordinate system orientation Euler angle expression in original coordinate system, unit degrees

b

double

B component of transformed coordinate system orientation Euler angle expression in original coordinate system, unit degrees

c

double

C component of transformed coordinate system orientation Euler angle expression in original coordinate system, unit degrees

Euler angles have 12 different Euler angle expression methods according to different rotation axis sequences. ZYX-type Euler angles are used here, meaning the sequence for transforming from initial coordinate system orientation to transformed coordinate system orientation is first rotating a degrees around z-axis, then rotating b degrees around new y-axis, finally rotating c degrees around new x-axis.

getjoint Function:

The getjoint function obtains robot axis positions corresponding to certain TCP poses, i.e., kinematic inverse solutions. Function prototype:

joint getjoint(pose p, tool t, wobj w)
Parameter Name Data Type Description

p

pose

Robot pose, refer to section 2.4.4

t

tool

Specified tool, refer to section 2.4.6

w

wobj

Reference workpiece coordinate system, refer to section 2.4.7

This function returns joint type, returning corresponding robot axis position information.

Usage example:

pose p = {x 763.869, y 207.323, z 1422.841, a 129.538, b 0.480, c 92.084, cfg 0}
print getjoint(p, $FLANGE, $WORLD)

The pose structure contains position and configuration information:

Member Name Data Type Description

b

double

B component of robot tool orientation Euler angle expression in current workpiece coordinate system, unit degrees

c

double

C component of robot tool orientation Euler angle expression in current workpiece coordinate system, unit degrees

cfg

int

Robot axis configuration. Since robots may have several different ways to make TCP reach the same position, the cfg parameter (values 0-7, representing 8 possible ways, where "beta" refers to fifth axis multiple angles) is needed to specify one way, thus uniquely determining one set of robot axis positions

turn

int

Used with cfg to determine inverse solution axis positions. Only the 6th bit of turn is used, bit0 represents axis 1, bit1 represents axis 2, and so on. When turn value is -1, automatically select solutions closest to nearest points; when turn value is 1, select solutions less than 0 for this axis; when turn value is 0, select solutions greater than 0 for this axis. This parameter may be used when axis motion range is greater than 360 degrees to assist selection, but is not needed in most other situations

ej1~ej6

double

External axis 1~6 positions, linear axis units are mm, rotational axis units are degrees

ELITE

ELITE robot controllers provide the get_inv_kinematics function for inverse kinematics calculations. This function can calculate target point joint angles based on target point poses and reference point joint angles.

Inverse Solution Function get_inv_kinematics:

Function syntax:

table get_inv_kinematics(table var1, table var2)

Parameter description: var1 is pose type target point pose; var2 is joint type reference point joint angles, reference points should be close to target points. If not written, current points are considered as reference. Function returns inverse solution results empty or table:joint type target point joint angles.

Usage example:

pose={378.538,212.504,134.055,-2.712,-0.791,2.553}
joint={10.081,-75.007,105.449,-70.694,98.434,89.481,0.000,0.000}
Inv_data=get_inv_kinematics(pose,joint)

pose={x,y,z,rx,ry,rz}, size 6 array, note that rx,ry,rz in pose are all in radians. joint={j1,j2,j3,j4,j5,j6,j7,j8} size 8 array.

Forward Solution Function get_fwd_kinematics:

ELITE also provides forward solution function get_fwd_kinematics for forward kinematics calculations:

table get_fwd_kinematics(table var1)

Parameter var1 is joint type target point joint angles. Function returns forward solution results or table:pose type target point poses.

Usage example:

joint={10.081,-75.007,105.449,-70.694,98.434,89.481,0.000,0.000}
fwd_data=get_fwd_kinematics(joint)

Data structure description: pose={x,y,z,rx,ry,rz} size 6 array; joint={j1,j2,j3,j4,j5,j6,j7,j8} size 6~8 array.

Common Issues

  1. Why does CalcJointT return ERR_ROBLIMIT error when the robot is currently at this position?

    This is a problem frequently encountered by ABB users. The reason is mismatched configuration parameters. If you call CalcJointT using configuration [0,2,0,-1] it will error, but using [0,1,0,0] configuration succeeds. The solution is to ensure input robtarget configuration matches actual robot configuration.

  2. How to handle Universal Robots "getInverse: Unable to find a solution"?

    This usually occurs when CB3 programs are loaded onto e-Series robots, due to mechanical differences (including higher bases, extended wrist joint 2, and longer tool plates) affecting tool position and joint angle relationships. Solutions include re-teaching path points, or for points where joint angles are important (such as home positions), selecting "Use Joint Angles" option.

  3. When does FANUC’s POS2JOINT function fail to work?

    FANUC users report POS2JOINT cannot perform conversions when encountering singularities, because infinite joint values (J4,J6) possibilities exist for Cartesian positions. Solutions include checking for proximity to singularities before calling, or using different reference joint positions.

  4. How to prevent safety issues caused by inverse kinematics calculations?

    Universal Robots provides is_within_safety_limits(pose) function to check if poses are within safety limits. Using this function before calling get_inverse_kin() can avoid error popups. For other manufacturers, verifying target positions are within workspace before calculations is recommended.

  5. Why are inverse kinematics calculations sometimes very slow?

    Possible reasons include: target positions near singularities, complex joint limit checking, or reference joint positions too far from targets. Optimizing reference joint position selection and avoiding known singularity areas is recommended.