forked from Modi1987/KST-Kuka-Sunrise-Toolbox
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgetEEFCartesianPosition.m
45 lines (36 loc) · 1.02 KB
/
getEEFCartesianPosition.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
function [ Pos ] = getEEFCartesianPosition( t )
%% This function is used to get the endeffector cartizian position of the KUKA iiwa 7 R 800.
%% Syntax:
% [ Pos ] = getEEFCartesianPosition( t )
%% About
% This function is used to get the endeffector Cartesian position of the KUKA iiwa 7 R 800.
% The position is of the media flange of the robot, and it is measured
% relative to the robot base frame.
%% Arreguments:
% t: is the TCP/IP connection
% Pos: is 1x3 cell array. Representing the X,Y and Z positions of the
% endeffector. The returned values are in (millimeters)
% Copyright, Mohammad SAFEEA, 3rd of May 2017
theCommand='Eef_pos';
fprintf(t, theCommand);
message=fgets(t);
%disp(message)
[P1,N]=getDoubleFromString(message);
for i=1:3
Pos{i}=P1{i};
end
end
function [jPos,j]=getDoubleFromString(message)
n=max(max(size(message)));
j=0;
numString=[];
for i=1:n
if message(i)=='_'
j=j+1;
jPos{j}=str2num(numString);
numString=[];
else
numString=[numString,message(i)];
end
end
end