-
Notifications
You must be signed in to change notification settings - Fork 5
/
mainNew.m
210 lines (172 loc) · 5.42 KB
/
mainNew.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
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
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
clc;
close all;
%clear all;
run('init_nao_parameters.m');
%% Global variables
global steptime;
global epsilon;
global dt;
global g;
global z0;
global T_leg_R;
global T_leg_L;
global T_global;
global P_COG;
global zG;
global dP_COG;
global start;
global limit_vel;
global max_height;
global mid_height;
global lambda_coeff;
global Alpha;
global step_time step_length
global animation;
global Ts;
global count
count=1;
%% Parameters for the simulation
start = 1; % not to be modified
pid_vel = 0;
limit_vel = 0;
plot_res = 1;
animation = 1;
%% Initialisation of the gravity constant
g = 9.81;
%% Initialisation of parameters for the PID
Alpha = 1;
Ki = 5;
%% Initiliastion of epsilon, threshold to stop the loop
epsilon = 0.0001;
%% Parameter for criterion
alpha=0;
%% Parameters of the trajectory
nb_points = 100;
nb_steps = 6;
swing_foot = 2; % not to be modified
step_time = .75;
step_length = 50*10^-3;
max_height = 20*10^-3;
mid_height = 2*10^-3;
lambda_coeff = 0.25;
Ts=step_time*nb_steps;
%%Initialisation of global reference transformation matrix
T_global=eye(4);
%% Initialisation of the time step
dt = step_time/(nb_points); % not to be modified
%% Initialisation of the time for the animation
steptime = dt; % not to be modified
%% Initialisation of the reference velocities
% velocity of both feet
%xi_Fi_traj = zeros(6,2,nb_points*nb_steps+1);
% velocity of both hands
xi_Hi_traj = zeros(6,2,nb_points*nb_steps+1);
% velocity of the waist
xi_B_traj = zeros(6,nb_points*nb_steps+1);
for plop=2:nb_points*nb_steps+1
% if mod(plop,2)==0
% xi_B_traj(3,plop)=.5;
% else
% %xi_B_traj(1,plop)=1;
% end
xi_B_traj(1,plop)=step_length/step_time ;
%xi_B_traj(2,plop)=.15*sin(plop*dt*pi*2);
xi_Hi_traj(1,1,plop) =step_length/step_time ;
xi_Hi_traj(1,2,plop) =step_length/step_time ;
%xi_B_traj(3,plop)=.05;
end
%initialize with values obtain from COG solved without angularmomentum
%derivtive
% load inx;
% load iny;
% for plop=2:nb_points*nb_steps+1
% xi_B_traj(1,plop)=x(plop,2);
% xi_B_traj(2,plop)=y(plop,2);;
% xi_Hi_traj(1,1,plop) =x(plop,2);
% xi_Hi_traj(1,2,plop) =x(plop,2);
% end
%initialize with values obtain from resolved momentum first iterqtion
% load initvB;
%
% xi_B_traj(2,:)=v_B(2,:);
% xi_B_traj(1:3,:)=v_B;
% xi_Hi_traj(1,1,:) =v_B(1,:);
% xi_Hi_traj(1,2,:) =v_B(1,:);
%% Initialisation of the accelerations
ddz_G = zeros(1,nb_points*nb_steps+1);
%% Initialisation of the starting position
theta_arm = zeros(4,2,nb_points*nb_steps+1);
theta_leg = zeros(6,2,nb_points*nb_steps+1);
run('init_robot_position.m');
t_arm_0 = theta_arm(:,:,1);
t_leg_0 = theta_leg(:,:,1);
t_arm_init = theta_arm(:,:,1);
t_leg_init = theta_leg(:,:,1);
%% Move the robot to its initial position
global separateChains
separateChains=0;
if separateChains==1
[chain_leg_R, chain_leg_L, chain_arm_R, chain_arm_L, chain_head] = ...
move_robot(t_leg_init,t_arm_init,theta_head,swing_foot,swing_foot,1);
else
[chain_leg_R, chain_leg_L, chain_arm_R, chain_arm_L, chain_head] = ...
move_robot2(t_leg_init,t_arm_init,theta_head,swing_foot,swing_foot,1);
end
T_leg_R = chain_leg_R(:,:,end);
T_leg_L = chain_leg_L(:,:,end);
% animate the motion
if animation == 1
animate(chain_leg_R, chain_leg_L, chain_arm_R, chain_arm_L, chain_head);
end
%% Initialisation of the height of the ground
z0 = 0;
zG = P_COG(3,1);
dP_COG = zeros(3,1);
%% Vectors for checking
real_pos = zeros(3,2,nb_steps*nb_points);
real_pos_arm = zeros(3,2,nb_steps*nb_points);
desired_pos = zeros(3,2,nb_steps*nb_points);
feet_state = [chain_leg_R(1:3,4,end), chain_leg_L(1:3,4,end)];
hands_state = [chain_arm_R(1:3,4,end), chain_arm_L(1:3,4,end)];
com_traj = zeros(3,2,nb_steps*nb_points);
[P_F,p_k,xi_Fi_traj,lambda_traj, n_k,swing]= trajectory_generation(nb_steps,nb_points,...
step_length,step_time,T_leg_R,T_leg_L,max_height,mid_height);
% for plop=2:nb_points*nb_steps+1
% if mod(plop,2)==0
% xi_B_traj(3,plop)=1;
% % xi_Fi_traj(5,2,3)=10;
% else
% xi_B_traj(3,plop)=1;
% end
% % xi_B_traj(1,:)=xi_Fi_traj(1,swing,:);
% % xi_Hi_traj(1,1,:) =xi_Fi_traj(1,swing,:) ;
% % xi_Hi_traj(1,2,:) =xi_Fi_traj(1,swing,:) ;
%
% end
% [theta_arm,theta_leg] = TestJacob (ddz_G, lambda_traj,p_k, alpha, n_k,t_arm_init,t_leg_init,xi_Fi_traj,xi_Hi_traj,xi_B_traj,P_COG,theta_head,swing);
test=0;
if test==0;
%see alg behaviour from last result
load results/VB
xi_B_traj(1:3,:) = v_B;
% xi_B_traj(1:2,:) = v_B(1:2,:);
xi_Hi_traj(1:2,1,:) =v_B(1:2,:);
xi_Hi_traj(1:2,2,:) =v_B(1:2,:);
% end of last result preparation
[theta_arm,theta_leg] = WalkingPatternGenerator (ddz_G, lambda_traj,p_k,...
alpha, n_k,t_arm_init,t_leg_init,xi_Fi_traj,xi_Hi_traj,xi_B_traj,P_COG,theta_head,swing);
savefile='results/thArm.mat';
save(savefile,'theta_arm');
savefile='results/thLeg.mat';
save(savefile,'theta_leg');
writeOutputFile(theta_arm,theta_leg);
else
load results/thArm
load results/thLeg
load results/VB
xi_B_traj(1:3,:) = v_B;
xi_Hi_traj(1:2,1,:) =v_B(1:2,:);
xi_Hi_traj(1:2,2,:) =v_B(1:2,:);
testRestults(ddz_G, lambda_traj,p_k, alpha, n_k,theta_arm,theta_leg,...
xi_Fi_traj,xi_Hi_traj,xi_B_traj,P_COG,theta_head,swing)
end