forked from Modi1987/KST-Kuka-Sunrise-Toolbox
-
Notifications
You must be signed in to change notification settings - Fork 0
/
kuka0_circles.m
99 lines (78 loc) · 3.33 KB
/
kuka0_circles.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
%% Example
% An example script, it is used to show how to use the arcs
% functions of the KUKA iiwa matlab toolbox
% First start the server on the KUKA iiwa controller
% Then run the following script in Matlab
% Note you have 60 seconds to connect to server after starting the
% application (MatlabToolboxServer) from the smart pad on the robot controller.
% Mohammad SAFEEA, 3rd of May 2017
close all,clear all;clc;
warning('off');
ip='172.31.1.147'; % The IP of the controller
% start a connection with the server
global t_Kuka;
t_Kuka=net_establishConnection( ip );
if ~exist('t_Kuka','var') || isempty(t_Kuka) || strcmp(t_Kuka.Status,'closed')
warning('Connection could not be establised, script aborted');
return;
else
%% Go to initial configuration
relVel=0.25; % over ride relative joint velocities
pos={0, -pi / 180 * 10, 0, -pi / 180 * 100, pi / 180 * 90,pi / 180 * 90, 0}; % initial cofiguration
movePTPJointSpace( t_Kuka , pos, relVel); % go to home position
%% Move in an arc, the orientation of EEF changes while performing the motion,
% The function utilized (movePTPCirc1OrintationInter)
% f2 is the final frame, at which the arc motion ends
% f1 is an intermidiate frame, through wich the robot passes while
% performing the motion.
f1=getEEFPos( t_Kuka );
f2=f1;
r=75;
f1{2}=f1{2}+r;
f1{3}=f1{3}-r;
f1{6}=f1{6}+pi/8;
f2{3}=f2{3}-2*r;
f2{6}=f2{6}+pi/2;
vel=150; % linear velocity of end-effector mm/sec
movePTPCirc1OrintationInter( t_Kuka , f1,f2, vel)
%% Move robot in joint space to some initial configuration
pinit={0,pi*20/180,0,-pi*70/180,0,pi*90/180,0}; % joint angles of initial confuguration
relVel=0.15; % the relative velocity
movePTPJointSpace( t_Kuka , pinit, relVel); % point to point motion in joint space
%% Move EEF -100 mm in Z direction
deltaX=0.0;deltaY=0;deltaZ=-100.; % relative displacemnets of end-effector
Pos{1}=deltaX;
Pos{2}=deltaY;
Pos{3}=deltaZ;
movePTPLineEefRelBase( t_Kuka , Pos, vel);
%% Store the current position in the memory
Cen=getEEFPos(t_Kuka); % Concider the current position as the center of the arcs
%% Move EEF 50mm in X direction
deltaX=100;deltaY=0;deltaZ=0.;
Pos{1}=deltaX;
Pos{2}=deltaY;
Pos{3}=deltaZ;
movePTPLineEefRelBase( t_Kuka , Pos, vel);
%% Store the current position in the memory
circle_Starting_Point=getEEFPos( t_Kuka ); % Consider the current point as circle starting point
%% Move in an arc, the arc is drawn on an incliend plane
% using the function ((movePTPArc_AC))
theta=pi/2; % the angle subtended by the arc at the center ((c))
k=[1;1;1]; % normal vector of the plane, on which the circle is drawn
c=[Cen{1};Cen{2};Cen{3}]; % the center of the arc
vel=100; % the motion velocity mm/sec
movePTPArc_AC(t_Kuka,theta,c,k,vel)
%% Go back to ((circle_Starting_Point)) coordinates
vel=150;
movePTPLineEEF( t_Kuka , circle_Starting_Point, vel);
%% Move in an arc, the arc is drawn in XY plane
% using the function ((movePTPArcXY_AC))
theta=1.98*pi; % the angle subtended by the arc at the center ((c))
c=[Cen{1};Cen{2}]; % the XY coordinate of the center of the arc
vel=150; % the motion velocity mm/sec
movePTPArcXY_AC(t_Kuka,theta,c,vel)
%% turn off the server
net_turnOffServer( t_Kuka );
fclose(t_Kuka);
end
warning('on');