2. RoboDK API (robodk package)

Warning

The RoboDK API was refactored with version 5.4.0.

These changes are backward compatible, but not forward compatible. Effectively, the robolink.py module is now a sub-module of the robodk package (robodk.robolink), and robodk.py is now split into different sub-modules (robodk.robomath, robodk.robodialogs, robodk.robofileio).

Before 5.4.0

Most of our examples used the import method below:

from robolink import *
from robodk import *
RDK = Robolink()
pose = eye()
ITEM_TYPE_ROBOT

After 5.4.0

You can use any of the following import methods:

from robodk import robolink, robomath
RDK = robolink.Robolink()
pose = robomath.eye()
robolink.ITEM_TYPE_ROBOT
from robodk.robolink import Robolink, ITEM_TYPE_ROBOT
from robodk.robomath import eye
RDK = Robolink()
pose = eye()
ITEM_TYPE_ROBOT
from robodk.robolink import *
from robodk.robomath import *
RDK = Robolink()
pose = eye()
ITEM_TYPE_ROBOT

The robodk package is the distributed entry point of the Python API. It is the common parent of all sub-packages and modules that constitute the Python API.

Overview of the RoboDK API:

2.2. robomath.py

The robomath module is a robotics toolbox for Python, based on Peter Corke’s Robotics Toolbox (regarding pose transformations): https://petercorke.com/toolboxes/robotics-toolbox/. The robomath sub-module includes the Mat class to represent transformations in 3D.

The following page provides a brief overview of the RoboDK API for Python: https://www.robodk.com/offline-programming

A summary regarding the RoboDK API is available in the documentation: https://robodk.com/doc/en/RoboDK-API.html

This is a robotics toolbox to facilitate operations with the RoboDK API and matrix (pose) operations. This toolbox includes a simple matrix class for pose transformations (Mat class).

This toolbox has been inspired from Peter Corke’s Robotics Toolbox: http://petercorke.com/wordpress/toolboxes/robotics-toolbox

In this module: pose = transformation matrix = homogeneous matrix = 4x4 matrix = Mat class

More information about the RoboDK API for Python here:

robodk.robomath.pi: float = 3.141592653589793

PI

robodk.robomath.pause(seconds)

Pause the execution for a specified duration.

Parameters

seconds (float) – time in seconds

robodk.robomath.sqrt(value)

Computes the square root of a given value.

Parameters

value (float) – Value to find the square root of.

Returns

Square root of the input value.

Return type

float

robodk.robomath.sqrtA(value)

Computes the square root of a value if it’s positive; returns 0 for non-positive values (differs from IEEE-754).

Parameters

value (float) – Value to compute the square root of.

Returns

Square root of the input value if positive, otherwise 0.

Return type

float

robodk.robomath.sin(value)

Calculates the sine of an angle given in radians.

Parameters

value (float) – Angle in radians.

Returns

Sine of the angle.

Return type

float

robodk.robomath.cos(value)

Calculates the cosine of an angle given in radians.

Parameters

value (float) – Angle in radians.

Returns

Cosine of the angle.

Return type

float

robodk.robomath.tan(value)

Calculates the tangent of an angle given in radians.

Parameters

value (float) – Angle in radians.

Returns

Tangent of the angle.

Return type

float

robodk.robomath.asin(value)

Calculates the arc sine of a value, result in radians.

Parameters

value (float) – Value to compute the arc sine for.

Returns

Arc sine of the input value in radians.

Return type

float

robodk.robomath.acos(value)

Calculates the arc cosine of a value, result in radians.

Parameters

value (float) – Value to compute the arc cosine for.

Returns

Arc cosine of the input value in radians.

Return type

float

robodk.robomath.atan2(y, x)

Calculates the angle of a point from the origin in the XY plane.

Parameters
  • y (float) – Y-coordinate of the point.

  • x (float) – X-coordinate of the point.

Returns

Angle of the point in radians.

Return type

float

robodk.robomath.name_2_id(str_name_id)

Extracts the numerical ID from a string containing a named object. For example: “Frame 3”, “Frame3”, “Fram3 3” returns 3.”

Parameters

str_name_id (str) – String containing the named object and its ID.

Returns

Numerical ID found in the string, or -1 if none found.

Return type

float

robodk.robomath.rotx(rx)

Returns a rotation matrix around the X axis (radians)

R_x(\theta) = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & c_\theta & -s_\theta & 0 \\ 0 & s_\theta & c_\theta & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

Parameters

rx (float) – rotation around X axis in radians

Return type

Mat

robodk.robomath.roty(ry)

Returns a rotation matrix around the Y axis (radians)

R_y(\theta) = \begin{bmatrix} c_\theta & 0 & s_\theta & 0 \\ 0 & 1 & 0 & 0 \\ -s_\theta & 0 & c_\theta & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

Parameters

ry (float) – rotation around Y axis in radians

Return type

Mat

robodk.robomath.rotz(rz)

Returns a rotation matrix around the Z axis (radians)

R_x(\theta) = \begin{bmatrix} c_\theta & -s_\theta & 0 & 0 \\ s_\theta & c_\theta & 0 & 0 \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

Parameters

rz (float) – rotation around Z axis in radians

Return type

Mat

robodk.robomath.transl(tx=0, ty=0, tz=0)

Returns a translation matrix (mm) given translations in each dimension. Supports passing inputs as a list through the tx argument, but this ignores ty and tz.

T(t_x, t_y, t_z) = \begin{bmatrix} 1 & 0 & 0 & t_x \\ 0 & 1 & 0 & t_y \\ 0 & 0 & 1 & t_z \\ 0 & 0 & 0 & 1 \end{bmatrix}

Parameters
  • tx (float or list of float, optional) – translation along the X axis (mm) or list of the supported parameters (i.e. [tx, ty, tz])

  • ty (float, optional) – translation along the Y axis (mm), defaults to 0

  • tz (float, optional) – translation along the Z axis (mm)

Return type

Mat

See also

rotx(), roty(), rotz()

robodk.robomath.RelTool(target_pose, x, y, z, rx=0, ry=0, rz=0)

Calculates a relative target with respect to the tool coordinates. This procedure has exactly the same behavior as ABB’s RelTool instruction. X,Y,Z are in mm, RX,RY,RZ are in degrees.

Parameters
  • target_pose (Mat) – Reference pose

  • x (float) – translation along the Tool X axis (mm)

  • y (float) – translation along the Tool Y axis (mm)

  • z (float) – translation along the Tool Z axis (mm)

  • rx (float) – rotation around the Tool X axis (deg), optional

  • ry (float) – rotation around the Tool Y axis (deg), optional

  • rz (float) – rotation around the Tool Z axis (deg), optional

Return type

Mat

robodk.robomath.Offset(target_pose, x, y, z, rx=0, ry=0, rz=0)

Calculates a relative target with respect to the reference frame coordinates. X,Y,Z are in mm, RX,RY,RZ are in degrees.

Parameters
  • target_pose (Mat) – Reference pose

  • x (float) – translation along the Reference X axis (mm)

  • y (float) – translation along the Reference Y axis (mm)

  • z (float) – translation along the Reference Z axis (mm)

  • rx (float) – rotation around the Reference X axis (deg), optional

  • ry (float) – rotation around the Reference Y axis (deg), optional

  • rz (float) – rotation around the Reference Z axis (deg), optional

Return type

Mat

robodk.robomath.point_Xaxis_2_pose(point, xaxis, zaxis_hint1=[0, 0, - 1], zaxis_hint2=[0, - 1, 0])

Returns a pose given the origin as a point, a X axis and a preferred orientation for the Z axis

Parameters
  • point (List[float]) –

  • xaxis (List[float]) –

  • zaxis_hint1 (List[float], default: [0, 0, -1]) –

  • zaxis_hint2 (List[float], default: [0, -1, 0]) –

Return type

Mat

robodk.robomath.point_Yaxis_2_pose(point, yaxis, zaxis_hint1=[0, 0, - 1], zaxis_hint2=[- 1, 0, 0])

Returns a pose given the origin as a point, a Y axis and a preferred orientation for the Z axis

Parameters
  • point (List[float]) –

  • yaxis (List[float]) –

  • zaxis_hint1 (List[float], default: [0, 0, -1]) –

  • zaxis_hint2 (List[float], default: [-1, 0, 0]) –

Return type

Mat

robodk.robomath.point_Zaxis_2_pose(point, zaxis, yaxis_hint1=[0, 0, 1], yaxis_hint2=[0, 1, 1])

Returns a pose given the origin as a point, a Z axis and a preferred orientation for the Y axis

Parameters
  • point (List[float]) –

  • zaxis (List[float]) –

  • yaxis_hint1 (List[float], default: [0, 0, 1]) –

  • yaxis_hint2 (List[float], default: [0, 1, 1]) –

Return type

Mat

robodk.robomath.eye(size=4)

Returns the identity matrix

T(t_x, t_y, t_z) = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}

Parameters

size (int) – square matrix size (4x4 Identity matrix by default, otherwise it is initialized to 0)

Return type

Mat

robodk.robomath.size(matrix, dim=None)

Returns the size of a matrix (m,n). Dim can be set to 0 to return m (rows) or 1 to return n (columns)

Parameters
  • matrix (Mat) – pose

  • dim (int) – dimension

Return type

Union[Tuple[int, int], int]

robodk.robomath.tr(matrix)

Returns the transpose of the matrix

Parameters

matrix (Mat) – pose

Return type

Mat

robodk.robomath.invH(matrix)

Returns the inverse of a homogeneous matrix

Parameters

matrix (Mat) – pose

Return type

Mat

robodk.robomath.catV(mat1, mat2)

Concatenate 2 matrices (vertical concatenation)

Parameters
  • mat1 (Mat) –

  • mat2 (Mat) –

Return type

Mat

robodk.robomath.catH(mat1, mat2)

Concatenate 2 matrices (horizontal concatenation)

Parameters
  • mat1 (Mat) –

  • mat2 (Mat) –

Return type

Mat

robodk.robomath.tic()

Start a stopwatch timer

robodk.robomath.toc()

Read the stopwatch timer

robodk.robomath.PosePP(x, y, z, r, p, w)

Create a pose from XYZRPW coordinates. The pose format is the one used by KUKA (XYZABC coordinates). This is function is the same as KUKA_2_Pose (with the difference that the input values are not a list). This function is used as “p” by the intermediate file when generating a robot program.

Parameters
  • x (float) –

  • y (float) –

  • z (float) –

  • r (float) –

  • p (float) –

  • w (float) –

Return type

Mat

robodk.robomath.pose_2_xyzrpw(H)

Calculates the equivalent position (mm) and Euler angles (deg) as an [x,y,z,r,p,w] array, given a pose. It returns the values that correspond to the following operation: transl(x,y,z)*rotz(w*pi/180)*roty(p*pi/180)*rotx(r*pi/180)

Parameters

H (Mat) – pose

Return type

List[float]

Returns

[x,y,z,r,p,w] in mm and deg

robodk.robomath.xyzrpw_2_pose(xyzrpw)

Calculates the pose from the position (mm) and Euler angles (deg), given a [x,y,z,r,p,w] array. The result is the same as calling: H = transl(x,y,z)*rotz(w*pi/180)*roty(p*pi/180)*rotx(r*pi/180)

Parameters

xyzrpw (List[float]) –

Return type

Mat

robodk.robomath.Pose(x, y, z, rxd, ryd, rzd)

Returns the pose (Mat) given the position (mm) and Euler angles (deg) as an array [x,y,z,rx,ry,rz]. The result is the same as calling: H = transl(x,y,z)*rotx(rx*pi/180)*roty(ry*pi/180)*rotz(rz*pi/180) This pose format is printed for homogeneous poses automatically. This Pose is the same representation used by Mecademic or Staubli robot controllers.

Parameters
  • tx (float) – position (X coordinate)

  • ty (float) – position (Y coordinate)

  • tz (float) – position (Z coordinate)

  • rxd (float) – first rotation in deg (X coordinate)

  • ryd (float) – first rotation in deg (Y coordinate)

  • rzd (float) – first rotation in deg (Z coordinate)

Parameters
  • x (float) –

  • y (float) –

  • z (float) –

Return type

Mat

robodk.robomath.TxyzRxyz_2_Pose(xyzrpw)

Returns the pose given the position (mm) and Euler angles (rad) as an array [x,y,z,rx,ry,rz]. The result is the same as calling: H = transl(x,y,z)*rotx(rx)*roty(ry)*rotz(rz)

Parameters

xyzrpw (list of float) – [x,y,z,rx,ry,rz] in mm and radians

Return type

Mat

robodk.robomath.Pose_2_TxyzRxyz(H)

Retrieve the position (mm) and Euler angles (rad) as an array [x,y,z,rx,ry,rz] given a pose. It returns the values that correspond to the following operation: H = transl(x,y,z)*rotx(rx)*roty(ry)*rotz(rz).

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Pose_2_Staubli(H)

Converts a pose (4x4 matrix) to a Staubli XYZWPR target

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Staubli_2_Pose(xyzwpr)

Converts a Staubli XYZWPR target to a pose (4x4 matrix)

Parameters

H (Mat) – pose

Parameters

xyzwpr (List[float]) –

Return type

Mat

robodk.robomath.Pose_2_Motoman(H)

Converts a pose (4x4 matrix) to a Motoman XYZWPR target (mm and deg)

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Pose_2_Fanuc(H)

Converts a pose (4x4 matrix) to a Fanuc XYZWPR target (mm and deg)

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Pose_2_Techman(H)

Converts a pose (4x4 matrix) to a Techman XYZWPR target (mm and deg)

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Motoman_2_Pose(xyzwpr)

Converts a Motoman target to a pose (4x4 matrix)

Parameters

xyzwpr (List[float]) –

Return type

Mat

robodk.robomath.Fanuc_2_Pose(xyzwpr)

Converts a Fanuc target to a pose (4x4 matrix)

Parameters

xyzwpr (List[float]) –

Return type

Mat

robodk.robomath.Techman_2_Pose(xyzwpr)

Converts a Techman target to a pose (4x4 matrix)

Parameters

xyzwpr (List[float]) –

Return type

Mat

robodk.robomath.Pose_2_KUKA(H)

Converts a pose (4x4 matrix) to an XYZABC KUKA target (Euler angles), required by KUKA KRC controllers.

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.KUKA_2_Pose(xyzrpw)

Converts a KUKA XYZABC target to a pose (4x4 matrix), required by KUKA KRC controllers.

Parameters

xyzrpw (List[float]) –

Return type

Mat

robodk.robomath.Adept_2_Pose(xyzrpw)

Converts an Adept XYZRPW target to a pose (4x4 matrix)

Parameters

xyzrpw (List[float]) –

Return type

Mat

robodk.robomath.Pose_2_Adept(H)

Converts a pose to an Adept target

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Pose_2_Catia(H)

Converts a pose to Catia or Solidworks format, in mm and deg. It returns the values that correspond to the following operation: H = transl(x,y,z)*rotz(a)*rotx(b)*rotz(c).

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Comau_2_Pose(xyzrpw)

Converts a Comau XYZRPW target to a pose (4x4 matrix), the same representation required by PDL Comau programs.

Parameters

xyzrpw (List[float]) –

Return type

Mat

robodk.robomath.Pose_2_Comau(H)

Converts a pose to a Comau target, the same representation required by PDL Comau programs.

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.Pose_2_Nachi(pose)

Converts a pose to a Nachi XYZRPW target

Parameters

pose (Mat) – pose

Return type

List[float]

robodk.robomath.Nachi_2_Pose(xyzwpr)

Converts a Nachi XYZRPW target to a pose (4x4 matrix)

Parameters

xyzwpr (List[float]) –

Return type

Mat

robodk.robomath.pose_2_quaternion(Ti)

Returns the quaternion orientation vector of a pose (4x4 matrix)

Parameters

Ti (Mat) – pose

Return type

List[float]

robodk.robomath.Pose_Split(pose1, pose2, delta_mm=1.0)

Create a sequence of poses that transitions from pose1 to pose2 by steps of delta_mm in mm (the first and last pose are not included in the list)

Parameters
  • pose1 (Mat) –

  • pose2 (Mat) –

  • delta_mm (float, default: 1.0) –

Return type

Mat

robodk.robomath.quaternion_2_pose(qin)

Returns the pose orientation matrix (4x4 matrix) given a quaternion orientation vector

Parameters

qin (list) – quaternions as 4 float values

Return type

Mat

robodk.robomath.Pose_2_ABB(H)

Converts a pose to an ABB target (using quaternion representation).

Parameters

H (Mat) – pose

Return type

List[float]

robodk.robomath.print_pose_ABB(pose)

Displays an ABB RAPID target (the same way it is displayed in IRC5 controllers).

Parameters

pose (Mat) – pose

robodk.robomath.Pose_2_UR(pose)

Calculate the p[x,y,z,u,v,w] position with rotation vector for a pose target. This is the same format required by Universal Robot controllers.

Parameters

pose (Mat) –

Return type

List[float]

robodk.robomath.UR_2_Pose(xyzwpr)

Calculate the pose target given a p[x,y,z,u,v,w] cartesian target with rotation vector. This is the same format required by Universal Robot controllers.

Parameters

xyzwpr (List[float]) –

Return type

Mat

robodk.robomath.dh(rz, tx=None, tz=None, rx=None)

Returns the Denavit-Hartenberg 4x4 matrix for a robot link. calling dh(rz,tx,tz,rx) is the same as using rotz(rz)*transl(tx,0,tz)*rotx(rx) calling dh(rz,tx,tz,rx) is the same as calling dh([rz,tx,tz,rx])

Parameters
  • rz (float) –

  • tx (Optional[float], default: None) –

  • tz (Optional[float], default: None) –

  • rx (Optional[float], default: None) –

Return type

Mat

robodk.robomath.dhm(rx, tx=None, tz=None, rz=None)

Returns the Denavit-Hartenberg Modified 4x4 matrix for a robot link (Craig 1986).

calling dhm(rx,tx,tz,rz) is the same as using rotx(rx)*transl(tx,0,tz)*rotz(rz)

calling dhm(rx,tx,tz,rz) is the same as calling dhm([rx,tx,tz,rz])

Parameters
  • rx (float) –

  • tx (Optional[float], default: None) –

  • tz (Optional[float], default: None) –

  • rz (Optional[float], default: None) –

Return type

Mat

robodk.robomath.joints_2_angles(jin, type)

Converts the robot encoders into angles between links depending on the type of the robot.

Parameters
  • jin (List[float]) –

  • type (int) –

Return type

List[float]

robodk.robomath.angles_2_joints(jin, type)

Converts the angles between links into the robot motor space depending on the type of the robot.

Parameters
  • jin (List[float]) –

  • type (int) –

Return type

List[float]

robodk.robomath.norm(p)

Returns the norm of a 3D vector

Parameters

p (List[float]) –

Return type

float

robodk.robomath.normalize3(a)

Returns the unitary vector

Parameters

a (List[float]) –

Return type

List[float]

robodk.robomath.cross(a, b)

Returns the cross product of two 3D vectors

Parameters
  • a (List[float]) –

  • b (List[float]) –

Return type

List[float]

robodk.robomath.dot(a, b)

Returns the dot product of two 3D vectors

Parameters
  • a (List[float]) –

  • b (List[float]) –

Return type

List[float]

robodk.robomath.angle3(a, b)

Returns the angle in radians of two 3D vectors

Parameters
  • a (List[float]) –

  • b (List[float]) –

Return type

float

robodk.robomath.pose_angle(pose)

Returns the angle in radians of a 4x4 matrix pose

Parameters

pose (Mat) – pose

Return type

float

robodk.robomath.pose_angle_between(pose1, pose2)

Returns the angle in radians between two poses (4x4 matrix pose)

Parameters
  • pose1 (Mat) –

  • pose2 (Mat) –

Return type

float

robodk.robomath.mult3(v, d)

Multiplies a 3D vector to a scalar

Parameters
  • v (List[float]) –

  • d (List[float]) –

Return type

List[float]

robodk.robomath.subs3(a, b)

Subtracts two 3D vectors c=a-b

Parameters
  • a (List[float]) –

  • b (List[float]) –

Return type

List[float]

robodk.robomath.add3(a, b)

Adds two 3D vectors c=a+b

Parameters
  • a (List[float]) –

  • b (List[float]) –

Return type

List[float]

robodk.robomath.distance(a, b)

Calculates the distance between two points

Parameters
  • a (List[float]) –

  • b (List[float]) –

Return type

float

robodk.robomath.pose_is_similar(a, b, tolerance=0.1)

Check if the pose is similar. Returns True if both poses are less than 0.1 mm or 0.1 deg appart. Optionally provide the tolerance in mm+deg

Parameters
  • a (List[float]) –

  • b (List[float]) –

  • tolerance (float, default: 0.1) –

Return type

bool

robodk.robomath.intersect_line_2_plane(pline, vline, pplane, vplane)

Calculates the intersection betweeen a line and a plane

Parameters
  • pline (List[float]) –

  • vline (List[float]) –

  • pplane (List[float]) –

  • vplane (List[float]) –

Return type

List[float]

robodk.robomath.proj_pt_2_plane(point, planepoint, planeABC)

Projects a point to a plane

Parameters
  • point (List[float]) –

  • planepoint (List[float]) –

  • planeABC (List[float]) –

Return type

List[float]

robodk.robomath.proj_pt_2_line(point, paxe, vaxe)

Projects a point to a line

Parameters
  • point (List[float]) –

  • paxe (List[float]) –

  • vaxe (List[float]) –

Return type

List[float]

robodk.robomath.fitPlane(points)

Returns the equation and normal for a best fit plane to a cloud of points.

Uses singular value decomposition to produce a least squares fit to a plane. Points must have centroid at [0, 0, 0]. Must provide at least 4 points.

Parameters

points (array-like) – a 3xN array of points. Each column represents one point.

Returns

pplane: the equation of the best-fit plane, in the form b(1)*X + b(2)*Y +b(3)*Z + b(4) = 0.

Return type

array_like

Returns

vplane: the normal vector of the best-fit plane.

Return type

list of floats

exception robodk.robomath.MatrixError

An exception class for Matrix

class robodk.robomath.Mat(rows=None, ncols=None)

Mat is a matrix object. The main purpose of this object is to represent a pose in the 3D space (position and orientation).

A pose is a 4x4 matrix that represents the position and orientation of one reference frame with respect to another one, in the 3D space.

Poses are commonly used in robotics to place objects, reference frames and targets with respect to each other.

Example:

from robodk.robolink import *           # import the robolink library
from robodk.robomath import *           # import the robomath library

RDK = Robolink()                        # connect to the RoboDK API
robot  = RDK.Item('', ITEM_TYPE_ROBOT)  # Retrieve a robot available in RoboDK
#target  = RDK.Item('Target 1')         # Retrieve a target (example)


pose = robot.Pose()                     # retrieve the current robot position as a pose (position of the active tool with respect to the active reference frame)
# target = target.Pose()                # the same can be applied to targets (taught position)

# Read the 4x4 pose matrix as [X,Y,Z , A,B,C] Euler representation (mm and deg): same representation as KUKA robots
XYZABC = Pose_2_KUKA(pose)
print(XYZABC)

# Read the 4x4 pose matrix as [X,Y,Z, q1,q2,q3,q4] quaternion representation (position in mm and orientation in quaternion): same representation as ABB robots (RAPID programming)
xyzq1234 = Pose_2_ABB(pose)
print(xyzq1234)

# Read the 4x4 pose matrix as [X,Y,Z, u,v,w] representation (position in mm and orientation vector in radians): same representation as Universal Robots
xyzuvw = Pose_2_UR(pose)
print(xyzuvw)

x,y,z,a,b,c = XYZABC                    # Use the KUKA representation (for example) and calculate a new pose based on the previous pose
XYZABC2 = [x,y,z+50,a,b,c+45]
pose2 = KUKA_2_Pose(XYZABC2)            # Convert the XYZABC array to a pose (4x4 matrix)

robot.MoveJ(pose2)                      # Make a joint move to the new position
# target.setPose(pose2)                  # We can also update the pose to targets, tools, reference frames, objects, ...
Parameters
  • rows (Union[int, List[List[float]], Mat, None], default: None) –

  • ncols (Optional[int], default: None) –

__init__(rows=None, ncols=None)

Initializes a new instance of the Mat class.

Parameters
  • rows (int or List[List[float]] or Mat) – Number of rows, a 2D list representing the matrix, or another Mat instance to clone.

  • ncols (int) – Number of columns (required if rows is an integer).

copy()

Creates a deep copy of the matrix.

Returns

A new instance of Mat that is a copy of this instance.

Return type

Mat

fromNumpy()

Convert a numpy array to a Mat matrix

Return type

Mat

toNumpy()

Return a copy of the Mat matrix as a numpy array

ColsCount()

Return the number of coumns. Same as len().

Return type

int

RowsCount()

Return the number of rows

Return type

int

Cols()

Retrieve the matrix as a list of columns (list of list of float).

Example:

>>> transl(10,20,30).Rows()
[[1, 0, 0, 10], [0, 1, 0, 20], [0, 0, 1, 30], [0, 0, 0, 1]]

>>> transl(10,20,30).Cols()
[[1, 0, 0, 0], [0, 1, 0, 0], [0, 0, 1, 0], [10, 20, 30, 1]]
Return type

List[List[float]]

Rows()

Get the matrix as a list of lists

Return type

List[List[float]]

Col(n)

“Get the Column n from the matrix

Parameters

n (int) –

Return type

List[float]

Row(n)

“Get the Row n from the matrix

Parameters

n (int) –

Return type

List[float]

tr()

Returns the transpose of the matrix

Return type

Mat

size(dim=None)

Returns the size of the matrix.

Parameters

dim (int) – Optional. If specified, returns the size of the specified dimension (0 for rows, 1 for columns).

Return type

Union[int, Tuple[int, int]]

Returns

The size of the matrix as a tuple (rows, columns), or the size of the specified dimension.

catV(mat2)

Concatenate with another matrix (vertical concatenation)

Parameters

mat2 (Mat) –

Return type

Mat

catH(mat2)

Concatenate with another matrix (horizontal concatenation)

Parameters

mat2 (Mat) –

Return type

Mat

eye(m=4)

Make identity matrix of size (mxm)

Parameters

m (int, default: 4) –

Return type

Mat

isHomogeneous()

Checks if the matrix is a homogeneous transformation matrix (4x4).

Returns

True if the matrix is homogeneous, False otherwise.

Return type

bool

RelTool(x, y, z, rx=0, ry=0, rz=0)

Calculates a relative target with respect to the tool coordinates. This procedure has exactly the same behavior as ABB’s RelTool instruction. X,Y,Z are in mm, RX,RY,RZ are in degrees.

Parameters
  • x (float) – translation along the Tool X axis (mm)

  • y (float) – translation along the Tool Y axis (mm)

  • z (float) – translation along the Tool Z axis (mm)

  • rx (float) – rotation around the Tool X axis (deg) (optional)

  • ry (float) – rotation around the Tool Y axis (deg) (optional)

  • rz (float) – rotation around the Tool Z axis (deg) (optional)

See also

Offset()

Return type

Mat

Offset(x, y, z, rx=0, ry=0, rz=0)

Calculates a relative target with respect to this pose. X,Y,Z are in mm, RX,RY,RZ are in degrees.

Parameters
  • x (float) – translation along the Reference X axis (mm)

  • y (float) – translation along the Reference Y axis (mm)

  • z (float) – translation along the Reference Z axis (mm)

  • rx (float) – rotation around the Reference X axis (deg) (optional)

  • ry (float) – rotation around the Reference Y axis (deg) (optional)

  • rz (float) – rotation around the Reference Z axis (deg) (optional)

See also

RelTool()

Return type

Mat

invH()

Returns the inverse of the matrix. Assumes the matrix is homogeneous.

Returns

The inverse of the matrix.

Return type

Mat

Raises

MatrixError – If the matrix is not homogeneous.

inv()

Returns the inverse of the matrix. Assumes the matrix is homogeneous.

Returns

The inverse of the matrix.

Return type

Mat

tolist()

Returns the first column of the matrix as a list

Return type

List[float]

list()

Returns the first column of the matrix as a list

Return type

List[float]

list2()

Returns the matrix as list of lists (one list per column)

Return type

list

Pos()

Extracts the translation part of a homogeneous transformation matrix.

Returns

The translation vector [X, Y, Z].

Return type

List[float]

VX()

Extracts the X-axis vector from a homogeneous transformation matrix.

Returns

The X-axis vector [Xx, Xy, Xz].

Return type

List[float]

VY()

Extracts the Y-axis vector from a homogeneous transformation matrix.

Returns

The Y-axis vector [Yx, Yy, Yz].

Return type

List[float]

VZ()

Extracts the Z-axis vector from a homogeneous transformation matrix.

Returns

The Z-axis vector [Zx, Zy, Zz].

Return type

List[float]

Rot33()

Returns the sub 3x3 rotation matrix

setPos(newpos)

Sets the translation part of a homogeneous transformation matrix.

Parameters

newpos (List[float] or Mat) – The new translation vector [X, Y, Z].

Returns

The matrix after setting the new position.

Return type

Mat

setVX(v_xyz)

Sets the X-axis vector of a homogeneous transformation matrix.

Parameters

v_xyz (List[float] or Mat) – The new X-axis vector [Xx, Xy, Xz].

Returns

The matrix after setting the new X-axis vector.

Return type

Mat

setVY(v_xyz)

Sets the Y-axis vector of a homogeneous transformation matrix.

Parameters

v_xyz (List[float] or Mat) – The new Y-axis vector [Yx, Yy, Yz].

Returns

The matrix after setting the new Y-axis vector.

Return type

Mat

setVZ(v_xyz)

Sets the Z-axis vector of a homogeneous transformation matrix.

Parameters

v_xyz (List[float] or Mat) – The new Z-axis vector [Zx, Zy, Zz].

Returns

The matrix after setting the new Z-axis vector.

Return type

Mat

translationPose()

Return the translation pose of this matrix. The rotation returned is set to identity (assumes that a 4x4 homogeneous matrix is being used)

Return type

Mat

rotationPose()

Return the rotation pose of this matrix. The position returned is set to [0,0,0] (assumes that a 4x4 homogeneous matrix is being used)

Return type

Mat

SaveCSV(strfile)

Save the Mat Matrix to a CSV (Comma Separated Values) file. The file can be easily opened as a spreadsheet such as Excel.

See also

SaveMat(), SaveList(), LoadList(), LoadMat()

Parameters

strfile (str) –

SaveMat(strfile, separator=',')

Save the Mat Matrix to a CSV or TXT file

See also

SaveCSV(), SaveList(), LoadList(), LoadMat()

Parameters
  • strfile (str) –

  • separator (str, default: ',') –

2.3. robodialogs.py

The robodialogs sub-module is a dialogs toolbox. It contains, open and save file dialogs, message prompts, input dialogs etc.

This module is a dialog toolbox for the RoboDK API and RoboDK Add-ins. This toolbox includes user prompts, open file dialogs, messages, etc.

More information about the RoboDK API for Python here:

robodk.robodialogs.FILE_TYPES_ALL = ('All Files', '.*')

File type filter for all files

robodk.robodialogs.FILE_TYPES_ROBODK = ('RoboDK Files', '.sld .rdk .robot .tool .rdka .rdkbak .rdkp .py')

File type filter for RoboDK files

robodk.robodialogs.FILE_TYPES_3D_OBJECT = ('3D Object Files', '.sld .stl .iges .igs .step .stp .obj .slp .3ds .dae .blend .wrl .wrml')

File type filter for 3D object files

robodk.robodialogs.FILE_TYPES_TEXT = ('Text Files', '.txt .csv')

File type filter for text files

robodk.robodialogs.FILE_TYPES_IMG = ('Image Files', '.png .jpg')

File type filter for image files

robodk.robodialogs.FILE_TYPES_CAM = ('CAM Files', '.cnc .nc .apt .gcode .ngc .nci .anc .dxf .aptsource .cls .acl .cl .clt .ncl .knc')

File type filter for CAD/CAM files

robodk.robodialogs.FILE_TYPES_ROBOT = ('Robot Files', '.mod .src .ls .jbi .prm .script .urp')

File type filter for robot files

robodk.robodialogs.getOpenFile(path_preference='C:/RoboDK/Library/', strfile='', strtitle='Open File', defaultextension='.*', filetypes=[('All Files', '.*'), ('RoboDK Files', '.sld .rdk .robot .tool .rdka .rdkbak .rdkp .py'), ('3D Object Files', '.sld .stl .iges .igs .step .stp .obj .slp .3ds .dae .blend .wrl .wrml'), ('Text Files', '.txt .csv'), ('Image Files', '.png .jpg'), ('CAM Files', '.cnc .nc .apt .gcode .ngc .nci .anc .dxf .aptsource .cls .acl .cl .clt .ncl .knc'), ('Robot Files', '.mod .src .ls .jbi .prm .script .urp')])

Deprecated since version 5.5: Obsolete. Use getOpenFileName() instead.

Pop up a file dialog window to select a file to open. Returns a file object opened in read-only mode. Use returned value.name to retrieve the file path.

Parameters
  • path_preference (str) – The initial folder path, optional

  • strfile (str) – The initial file name (with extension), optional

  • strtitle (str) – The dialog title, optional

  • defaultextension (str) – The initial file extension filter, e.g. ‘.*’

  • filetypes (list of tuples of str) – The available file type filters, e.g. ‘[(‘All Files’, ‘.*’), (‘Text Files’, ‘.txt .csv’)]’

Returns

An read-only handle to the file, or None if the user cancels

Return type

TextIOWrapper

robodk.robodialogs.getSaveFile(path_preference='C:/RoboDK/Library/', strfile='', strtitle='Save As', defaultextension='.*', filetypes=[('All Files', '.*'), ('RoboDK Files', '.sld .rdk .robot .tool .rdka .rdkbak .rdkp .py'), ('3D Object Files', '.sld .stl .iges .igs .step .stp .obj .slp .3ds .dae .blend .wrl .wrml'), ('Text Files', '.txt .csv'), ('Image Files', '.png .jpg'), ('CAM Files', '.cnc .nc .apt .gcode .ngc .nci .anc .dxf .aptsource .cls .acl .cl .clt .ncl .knc'), ('Robot Files', '.mod .src .ls .jbi .prm .script .urp')])

Deprecated since version 5.5: Obsolete. Use getSaveFileName() instead.

Pop up a file dialog window to select a file to save. Returns a file object opened in write-only mode. Use returned value.name to retrieve the file path.

Parameters
  • path_preference (str) – The initial folder path, optional

  • strfile (str) – The initial file name (with extension), optional

  • strtitle (str) – The dialog title, optional

  • defaultextension (str) – The initial file extension filter, e.g. ‘.*’

  • filetypes (list of tuples of str) – The available file type filters, e.g. ‘[(‘All Files’, ‘.*’), (‘Text Files’, ‘.txt .csv’)]’

Returns

An write-only handle to the file, or None if the user cancels

Return type

TextIOWrapper

robodk.robodialogs.getOpenFileName(path_preference='C:/RoboDK/Library/', strfile='', strtitle='Open File', defaultextension='.*', filetypes=[('All Files', '.*'), ('RoboDK Files', '.sld .rdk .robot .tool .rdka .rdkbak .rdkp .py'), ('3D Object Files', '.sld .stl .iges .igs .step .stp .obj .slp .3ds .dae .blend .wrl .wrml'), ('Text Files', '.txt .csv'), ('Image Files', '.png .jpg'), ('CAM Files', '.cnc .nc .apt .gcode .ngc .nci .anc .dxf .aptsource .cls .acl .cl .clt .ncl .knc'), ('Robot Files', '.mod .src .ls .jbi .prm .script .urp')])

Pop up a file dialog window to select a file to open. Returns the file path as a string.

Parameters
  • path_preference (str) – The initial folder path, optional

  • strfile (str) – The initial file name (with extension), optional

  • strtitle (str) – The dialog title, optional

  • defaultextension (str) – The initial file extension filter, e.g. ‘.*’

  • filetypes (list of tuples of str) – The available file type filters, e.g. ‘[(‘All Files’, ‘.*’), (‘Text Files’, ‘.txt .csv’)]’

Returns

The file path, or None if the user cancels

Return type

str

robodk.robodialogs.getOpenFileNames(path_preference='C:/RoboDK/Library/', strfile='', strtitle='Open File(s)', defaultextension='.*', filetypes=[('All Files', '.*'), ('RoboDK Files', '.sld .rdk .robot .tool .rdka .rdkbak .rdkp .py'), ('3D Object Files', '.sld .stl .iges .igs .step .stp .obj .slp .3ds .dae .blend .wrl .wrml'), ('Text Files', '.txt .csv'), ('Image Files', '.png .jpg'), ('CAM Files', '.cnc .nc .apt .gcode .ngc .nci .anc .dxf .aptsource .cls .acl .cl .clt .ncl .knc'), ('Robot Files', '.mod .src .ls .jbi .prm .script .urp')])

Pop up a file dialog window to select one or more file to open. Returns the file path as a list of string.

Parameters
  • path_preference (str) – The initial folder path, optional

  • strfile (str) – The initial file name (with extension), optional

  • strtitle (str) – The dialog title, optional

  • defaultextension (str) – The initial file extension filter, e.g. ‘.*’

  • filetypes (list of tuples of str) – The available file type filters, e.g. ‘[(‘All Files’, ‘.*’), (‘Text Files’, ‘.txt .csv’)]’

Returns

A list of file path(s), or None if the user cancels

Return type

list of str

robodk.robodialogs.getSaveFileName(path_preference='C:/RoboDK/Library/', strfile='', strtitle='Save As', defaultextension='.*', filetypes=[('All Files', '.*'), ('RoboDK Files', '.sld .rdk .robot .tool .rdka .rdkbak .rdkp .py'), ('3D Object Files', '.sld .stl .iges .igs .step .stp .obj .slp .3ds .dae .blend .wrl .wrml'), ('Text Files', '.txt .csv'), ('Image Files', '.png .jpg'), ('CAM Files', '.cnc .nc .apt .gcode .ngc .nci .anc .dxf .aptsource .cls .acl .cl .clt .ncl .knc'), ('Robot Files', '.mod .src .ls .jbi .prm .script .urp')])