-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathQ1.asv
145 lines (97 loc) · 3.44 KB
/
Q1.asv
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
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
clear all;
close all;
clc;
addpath 'C:\Program Files\Polyspace\R2019b\examples\robotics\main' %gitignore
a=1;
b=1;
c=1;
% Create two platforms
platform1 = collisionBox(0.5,0.5,0.5);
platform1.Pose = trvec2tform([a b/2 c]);
platform2 = collisionCylinder(0.2,0.4);
platform2.Pose = trvec2tform([a/2 b/2 c/2]);
% Store in a cell array for collision-checking
worldCollisionArray = {platform1 platform2};
robot = loadrobot("kinovaGen3","DataFormat","column");
% Generate an array of collision objects from the visuals of the associated tree
collisionArray = exampleHelperManipCollisionsFromVisuals(robot);
startPose = trvec2tform([a/2,0.0001,c/2-0.0001])*axang2tform([1 0 0 -pi/2]);
endPose = trvec2tform([0.0001,0.85,0.0001])*axang2tform([1 0 0 -pi/2]);
%rng(113); % random seed
ik = inverseKinematics("RigidBodyTree",robot);
weights = ones(1,6);
startConfig = ik("EndEffector_Link",startPose,weights,robot.homeConfiguration);
endConfig = ik("EndEffector_Link",endPose,weights,robot.homeConfiguration);
%%
% Plot the
ax2 = exampleHelperVisualizeCollisionEnvironment(worldCollisionArray);
show(robot,startConfig,"Parent",ax2);
%show(robot,endConfig);
np = 300;
% prm
random_q = [5 ;5 ;5 ;5 ;5 ;5; 0 ].*rand(7,np) - 2.5;
endConfig(7) = -2.5 ;
startConfig(7) = -2.5 ;
okPoint = false(np,1);
for i=1:np
conf = random_q(:,i);
pos = getTransform(robot,conf,'EndEffector_Link');
if all(pos(1:3,4)>0) && pos(3,4)<c/2
[collision,~,~] = exampleHelperManipCheckCollisions(robot,collisionArray,worldCollisionArray,conf,false);
okPoint(i) = ~collision;
% draw
if okPoint(i)==1
plot3(pos(1,4),pos(2,4),pos(3,4),'b.','MarkerSize',15);
else
plot3(pos(1,4),pos(2,4),pos(3,4),'r.','MarkerSize',10);
end
end
end
random_q = random_q(:,okPoint);
random_q =[ random_q , startConfig , endConfig ];
np = length(random_q(1,:))
%%
adjMat = ones(np)*inf;
for i=1:np
conf = random_q(:,i);
pos = getTransform(robot,conf,'EndEffector_Link');
[idxs,mD] = knnsearch(random_q',conf','K',6);
for i2 = 1:length(idxs)
conf2 = random_q(:,idxs(i2));
pos2 = getTransform(robot,conf2,'EndEffector_Link');
q2 = trapveltraj([conf,conf2],5);
anyCollision = false;
for i3 = 2:length(q2(1,:))-1
pos3 = getTransform(robot,q2(:,i3),'EndEffector_Link');
[isCollision,~,~] = exampleHelperManipCheckCollisions(robot,collisionArray,worldCollisionArray,q2(:,i3),false);
anyCollision = anyCollision || isCollision;
anyCollision = anyCollision ||~(all(pos3(1:3,4)>0) && pos3(3,4)<c/2);
if anyCollision
break
end
end
if (anyCollision==1)
plt=plot3( [pos(1,4) pos2(1,4)],[pos(2,4) pos2(2,4)],[pos(3,4) pos2(3,4)],'r--','LineWidth',0.4 );
plt.Color(4) = 0.5;
else
plot3( [pos(1,4) pos2(1,4)],[pos(2,4) pos2(2,4)],[pos(3,4) pos2(3,4)],'b-' ,'LineWidth',0.7)
adjMat(i,idxs(i2))=mD(i2);
adjMat(idxs(i2),i)=adjMat(i,idxs(i2));
end
end
end
%%
path_idxs = dijkstra(np, adjMat, np-1, np);
q = trapveltraj(random_q(:,path_idxs),250);
for i = 1:length(q)
pos=getTransform(robot,q(:,i),'EndEffector_Link');
plot3(pos(1,4),pos(2,4),pos(3,4),'g.','MarkerSize',10);
end
%%
% % animate
%{
for i = 1:length(q)
show(robot,q(:,i),"Parent",ax2,"PreservePlot",false);
drawnow
end
%}