RoboDK API for MATLAB

This example script demonstrates the integration of RoboDK's API with MATLAB. It is designed to provide a basic understanding of how to interact with RoboDK's API within the MATLAB environment. The example does not aim to fulfill any specific application needs but rather to showcase the API's capabilities and usage in MATLAB.

All necessary API dependencies are included in the current directory.

The script automatically loads "Example 06b", which is part of the default installation in RoboDK's "Library" folder. This example is intended solely for educational purposes to illustrate the usage of the RoboDK API within MATLAB. It is not designed to achieve a particular task.

Additional Resources:

  • For detailed documentation on the Robolink class, type "doc Robolink" in the MATLAB Command Window.
  • For information on the RobolinkItem class, type "doc RobolinkItem".
  • To view more examples demonstrating the use of the RoboDK API, type "showdemo Example_RoboDK".
  • For the RoboDK MATLAB API documentation, visit: https://robodk.com/doc/en/RoboDK-API.html#MatlabAPI.

Contents

How to load a station from disk

clc
clear
close all

% Generate a Robolink object RDK. This object interfaces with RoboDK.
RDK = Robolink;

% Get the library path
% path = "C:\RoboDK\Library"; % Since RoboDK 5.5, PATH_LIBRARY points to Documents
path = RDK.getParam('PATH_LIBRARY');

% Open example 1
% RDK.AddFile([path,'Example 01 - Pick and place.rdk']); % prior to RoboDK 4.0.0
station = RDK.AddFile([path, 'Example-06.b-Pick and place 2 tables.rdk']);

if ~station.Valid()
    path = ['C:/RoboDK/Library/'];
    station = RDK.AddFile([path, 'Example-06.b-Pick and place 2 tables.rdk']);

    if ~station.Valid()
        RDK.ShowMessage(sprintf('This example requires Example-06.b-Pick and place 2 tables.rdk library folder:<br>%s.', library_path))
        return
    end
end

% Display a list of all items
fprintf('Available items in the station:\n');
disp(RDK.ItemList(-1, 1));

% Get one item by its name
program = RDK.Item('Pick and place', RDK.ITEM_TYPE_PROGRAM);

% Start "Pick and place" program
program.RunProgram();

% Alternative call to run the program
% program = RDK.Item('Pick and place').RunProgram();

% Another alternative call to run the same program
% RDK.RunProgram('Pick and place');

% return;
Warning: File doesn't exist: C:/Users/RoboDK/Documents/RoboDK/Example-06.b-Pick
and place 2 tables.rdk 
Available items in the station:
  Columns 1 through 3

    {'Example 1 - Pic…'}    {'ABB IRB 1600-8/…'}    {'ABB IRB 1600-8/…'}

  Columns 4 through 8

    {'Tool'}    {'Table 1'}    {'Approach'}    {'Target b1'}    {'Target b2'}

  Columns 9 through 13

    {'Target b3'}    {'Target b4'}    {'Target b5'}    {'base'}    {'ball 1'}

  Columns 14 through 18

    {'ball 2'}    {'ball 3'}    {'ball 4'}    {'ball 5'}    {'Table 2'}

  Columns 19 through 21

    {'base'}    {'Pick and place'}    {'Replace objects'}

How to retrieve objects from the station and modify them

% Get some items in the station by their name. Each item is visible in the
% current project tree

robot = RDK.Item('ABB IRB 1600-8/1.45', RDK.ITEM_TYPE_ROBOT);
fprintf('Robot selected:\t%s\n', robot.Name());
robot.setVisible(1);
% We can validate the type of each item by calling:
% robot.Type()
% We can retreive the item position with respect to the station with PoseAbs()
% robot.PoseAbs()

frameref = robot.Parent();
fprintf('Robot reference selected:\t%s\n', frameref.Name());

object = RDK.Item('base', RDK.ITEM_TYPE_OBJECT);
fprintf('Object selected:\t%s\n', object.Name());

ball = RDK.Item('ball');
fprintf('Ball selected:\t%s\n', ball.Name());

frametable = RDK.Item('Table 1', RDK.ITEM_TYPE_FRAME);
fprintf('Table selected:\t%s\n', frametable.Name());

tool = RDK.Item('Tool', RDK.ITEM_TYPE_TOOL);
fprintf('Tool selected:\t%s\n', tool.Name());

target1 = RDK.Item('Target b1', RDK.ITEM_TYPE_TARGET);
fprintf('Target 1 selected:\t%s\n', target1.Name());

target2 = RDK.Item('Target b3', RDK.ITEM_TYPE_TARGET);
fprintf('Target 2 selected:\t%s\n', target2.Name());

% return
Robot selected:	ABB IRB 1600-8/1.45
Robot reference selected:	ABB IRB 1600-8/1.45 Base
Object selected:	base
Ball selected:	ball 1
Table selected:	Table 1
Tool selected:	Tool
Target 1 selected:	Target b1
Target 2 selected:	Target b3

How to generate a robot program

% Clean up previous items automatically generated by this script
% the keyword "macro" is used if we want to delete any items when the
% script is executed again.
tic()

while 1
    item = RDK.Item('macro');

    if item.Valid() == 0
        % Iterate until there are no items with the "macro" name
        break
    end

    % if Valid() returns 1 it means that an item was found
    % if so, delete the item in the RoboDK station
    item.Delete();
end

% Set the home joints
jhome = [0, 0, 0, 0, 30, 0];

% Set the robot at the home position
robot.setJoints(jhome);

% Turn off rendering (faster)
RDK.Render(0);

% Get the tool pose
Htcp = tool.PoseTool();

% Create a reference frame with respect to the robot base reference
ref = RDK.AddFrame('Frame macro', frameref);
% Set the reference frame at coordinates XYZ, rotation of 90deg about Y plus rotation of 180 deg about Z
Hframe = transl(750, 250, 500) * roty(pi / 2) * rotz(pi);
ref.setPose(Hframe);

% Set the robot's reference frame as the reference we just cretaed
robot.setPoseFrame(ref);
% Set the tool frame
robot.setPoseTool(Htcp);

% Get the position of the TCP wrt the robot base
Hhome = inv(Hframe) * robot.SolveFK(jhome) * Htcp;

% Create a new program "prog"
prog = RDK.AddProgram('Prog macro');

% Create a joint target home
target = RDK.AddTarget('Home', ref, robot);
target.setAsJointTarget();
target.setJoints(jhome)
% Add joint movement into the program
prog.MoveJ(target);

% Generate a sequence of targets and move along the targets (linear move)
angleY = 0;

for dy = 600:-100:100
    targetname = sprintf('Target TY=%i RY=%i', dy, angleY);
    target = RDK.AddTarget(targetname, ref, robot);
    % Move along Z direction of the reference frame
    pose = transl(0, dy, 0);
    % Keep the same orientation as home orientation
    pose(1:3, 1:3) = Hhome(1:3, 1:3);
    pose = pose * roty(angleY * pi / 180);
    target.setPose(pose);
    prog.MoveL(target);
    angleY = angleY + 20;
end

% Set automatic render on every call
RDK.Render(1);

% Run the program we just created
prog.RunProgram();

% Wait for the movement to finish
while robot.Busy()
    pause(1);
    fprintf('Waiting for the robot to finish...\n');
end

% Run the program once again
fprintf('Running the program again...\n');
prog.RunProgram();
Waiting for the robot to finish...
Running the program again...

How to change the parent that an item is attached to

% Change the support of a target
% The final result of the operations made to target1 and target2 is the same
Htarget = target1.Pose();
target1.setParentStatic(frameref);
target1.setPose(Htarget);

target2.setParent(frameref);

% We can list the items that depend on an item
childs = frametable.Childs();

for i = 1:numel(childs)
    name = childs{i}.Name();
    newname = [name, ' modified'];
    visible = childs{i}.Visible();
    childs{i}.setName(newname);
    fprintf('%s %i\n', newname, visible);
end
Approach modified 1
Target b2 modified 1
Target b4 modified 1
Target b5 modified 1
base modified 1
ball 1 modified 1
ball 2 modified 1
ball 3 modified 1
ball 4 modified 1

How to Attach/Detach an object to the robot tool

% Attach the closest object to the tool
attached = tool.AttachClosest();
% If we know what object we want to attach, we can use this function
% instead: object.setParentStatic(tool);
if attached.Valid()
    attachedname = attached.Name();
    fprintf('Attached: %s\n', attachedname);
else
    % The tolerance can be changed in:
    % Tools->Options->General tab->Maximum distance to attach an object to
    % a robot tool (default is 1000 mm)
    fprintf('No object is close enough\n');
end

pause(2);
tool.DetachAll();
fprintf('Detached all objects\n');
No object is close enough
Detached all objects

How to scale an object and how to detect collisions

% Replace objects (we call the program previously set in example 1)
RDK.Item('Replace objects', RDK.ITEM_TYPE_PROGRAM).RunProgram();

% Verify if a joint movement from j1 to j2 is free of colllision
j1 = [-100, -50, -50, -50, -50, -50];
j2 = [100, 50, 50, 50, 50, 50];
collision = robot.MoveJ_Test(j1, j2, 1);
disp(collision)
% Activate the trace to see what path the robot tries to make
% To activate the trace: Tools->Trace->Active (ALT+T)

% Detect collisions: returns the number of pairs of objects in a collision state
pairs = RDK.Collisions();
fprintf('Pairs collided: %i\n', pairs);

% Scale the geometry of an object, scale can be one number or a scale per axis
object.Scale([10, 10, 0.5]);

% Detect the intersection between a line and any object
p1 = [1000; 0; 8000];
p2 = [1000; 0; 0];
[collision, itempicked, xyz] = RDK.Collision_Line(p1, p2);

if collision % or itempicked.Valid()
    fprintf('Line from p1 to p2 collides with %s\n', itempicked.Name());
    % Create a point in the intersection to display collision
    ball.Copy();
    newball = RDK.Paste();
    % Set this ball at the collision point
    newball.setPose(transl(xyz(1), xyz(2), xyz(3)));
    newball.Scale(0.5); % Make this ball 50 % of the original size
    newball.Recolor([1 0 0]); % Make it a red ball
end
   1

Pairs collided: 1
Line from p1 to p2 collides with base modified

How to move the robot programmaticall without creating a program

% Replace objects (we call the program previously set in example 1)
RDK.Item('Replace objects', RDK.ITEM_TYPE_PROGRAM).RunProgram();

% RDK.setRunMode(1); % this performs a quick validation without showing the dynamic movement
% (1 = RUNMODE_QUICKVALIDATE)

fprintf('Moving by target item...\n');
robot.setPoseFrame(frametable);
RDK.setSimulationSpeed(10);

for i = 1:2
    robot.setSpeed(10000, 1000);
    robot.MoveJ(target1);
    robot.setSpeed(100, 200);
    robot.MoveL(target2);

end

fprintf('Moving by joints...\n');
J1 = [0, 0, 0, 0, 50, 0];
J2 = [40, 30, -30, 0, 50, 0];

for i = 1:2
    robot.MoveJ(J1);
    robot.MoveL(J2);
end

fprintf('Moving by pose...\n');
% Follow these steps to retreive a pose:
% 1-Double click a robot
% 2-Copy the pose of the Tool frame with respect to the User Frame (as a Matrix)
% 3-Paste it here
H1 = [-0.492404, -0.642788, -0.586824, -101.791308;
    -0.413176, 0.766044, -0.492404, 1265.638417;
    0.766044, 0.000000, -0.642788, 117.851733;
    0.000000, 0.000000, 0.000000, 1.000000];

H2 = [-0.759717, -0.280123, -0.586823, -323.957442;
    0.060192, 0.868282, -0.492405, 358.739694;
    0.647462, -0.409410, -0.642787, 239.313006;
    0.000000, 0.000000, 0.000000, 1.000000];

for i = 1:2
    robot.MoveJ(H1);
    robot.MoveL(H2);
end
Moving by target item...
Moving by joints...
Moving by pose...

How to calculate forward and inverse kinematics of a robot

% Get the current robot joints
fprintf('Current robot joints:\n');
joints = robot.Joints();
disp(joints);

% Get the current position of the TCP with respect to the reference frame
fprintf('Calculated pose for current joints:\n');
H_tcp_wrt_frame = robot.SolveFK(joints);
disp(H_tcp_wrt_frame);

% Calculate the joints to reach this position (should be the same as joints)
fprintf('Calculated robot joints from pose:\n');
joints2 = robot.SolveIK(H_tcp_wrt_frame);
disp(joints2);

% Calculate all solutions
fprintf('All solutions available for the selected position:\n');
joints3_all = robot.SolveIK_All(H_tcp_wrt_frame);
disp(joints3_all);

% Show the sequence in the slider bar in RoboDK
RDK.ShowSequence(joints3_all);

pause(1);
% Make joints 4 the solution to reach the target off by 100 mm in Z
joints4 = robot.SolveIK(H_tcp_wrt_frame * transl(0, 0, -100));
% Set the robot at the new position calculated
robot.setJoints(joints4);
Current robot joints:
  -56.8091  -22.9201   33.5814   47.6220   54.6902 -104.7797

Calculated pose for current joints:
   -0.5868   -0.2801    0.7597  305.0477
   -0.4924    0.8683   -0.0602 -394.7465
   -0.6428   -0.4094   -0.6475  978.1476
         0         0         0    1.0000

Calculated robot joints from pose:
  -56.8091  -22.9201   33.5814   47.6220   54.6902 -104.7797

All solutions available for the selected position:
  Columns 1 through 7

  -56.8091  -56.8091  123.1909  123.1909  -56.8091  -56.8091  123.1909
  -22.9201  -22.9201   -3.2918   -3.2918  -22.9201  -22.9201   -3.2918
   33.5814   33.5814 -192.6814 -192.6814   33.5814   33.5814 -192.6814
   47.6220 -132.3780 -129.3428   50.6572   47.6220 -132.3780 -129.3428
   54.6902  -54.6902   51.2124  -51.2124   54.6902  -54.6902   51.2124
 -104.7797   75.2203 -109.8131   70.1869  255.2203 -284.7797  250.1869
   10.0000   10.0000   10.0000   10.0000         0         0         0
    0.0000  180.0000  226.2628  226.2628  360.0000  180.0000  354.9666

  Column 8

  123.1909
   -3.2918
 -192.6814
   50.6572
  -51.2124
 -289.8131
         0
  226.2628

How to add targets to a program and use circular motion

RDK = Robolink();
robot = RDK.Item('', RDK.ITEM_TYPE_ROBOT);

% Get the current robot pose:
pose0 = robot.Pose();

% Add a new program:
prog = RDK.AddProgram('TestProgram');

% Create a linear move to the current robot position (MoveC is defined by 3
% points)
target0 = RDK.AddTarget('First Point');
target0.setAsCartesianTarget(); % default behavior
target0.setPose(pose0);
prog.MoveL(target0);

% Calculate the circular move:
pose1 = pose0 * transl(50, 0, 0);
pose2 = pose0 * transl(50, 50, 0);

% Add the first target for the circular move
target1 = RDK.AddTarget('Second Point');
target1.setAsCartesianTarget();
target1.setPose(pose1);

% Add the second target for the circular move
target2 = RDK.AddTarget('Third Point');
target2.setAsCartesianTarget();
target2.setPose(pose2);

% Add the circular move instruction:
prog.MoveC(target1, target2)

How to calculate inverse kinematics of a robot with a synchronized linear rail

% Start the API
RDK = Robolink();

% Retrieve the robot
robot = RDK.Item('', RDK.ITEM_TYPE_ROBOT);

% Make sure the robot is the robot arm, not the external axis (returns a
% pointer to itself if it is the robot already)
robot = robot.getLink(RDK.ITEM_TYPE_ROBOT);
disp(robot.Name());

robot.setJointLimits([-180; -180; -180; -180; -180; -180; 0], [+180; +180; +180; +180; +180; +180; 5000]);
[lower_limit, upper_limit] = robot.JointLimits();
disp(lower_limit)
disp(upper_limit)

joints = robot.JointsHome();
config = robot.JointsConfig(joints);
disp(config)

all_solutions = robot.SolveIK_All(robot.SolveFK(robot.Joints()));
disp(all_solutions)
ABB IRB 1600-8/1.45
  -180
  -180
  -180
  -180
  -180
  -180

   180
   180
   180
   180
   180
   180

     0
     0
     0
     0

  Columns 1 through 7

  -64.9691  -64.9691  -64.9691  -64.9691  115.0309  115.0309  115.0309
  -27.6557  -27.6557   76.9661   76.9661  -89.0434  -89.0434    1.3654
   29.7138   29.7138  150.2862  150.2862   11.0876   11.0876  168.9124
   46.2971 -133.7029  103.8452  -76.1548 -109.3352   70.6648 -130.9223
   66.4849  -66.4849  136.9424 -136.9424  135.3704 -135.3704   61.3200
 -103.9353   76.0647   27.3638 -152.6362  -17.5214  162.4786 -110.2446
   10.0000   10.0000   10.0000   10.0000   10.0000   10.0000   10.0000
    0.0000  180.0000  131.2992  203.4274  180.0000  266.4139  180.0000

  Column 8

  115.0309
    1.3654
  168.9124
   49.0777
  -61.3200
   69.7554
   10.0000
  180.0000

 

Privacy
Our website stores cookies as described in our cookie statement.
By using our website you accept the use of cookies.