-
Notifications
You must be signed in to change notification settings - Fork 14
/
Copy pathslipHopper.m
283 lines (233 loc) · 8.74 KB
/
slipHopper.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
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
% SLIPHOPPER simulates Spring Loaded Inverted Pendulum (SLIP)
% find limit cycles and then find Jacobian to evaluate linear stability
% Needs ODE113, FSOLVE, INTERP1.
% If you find bugs in this code please mail,
% Pranav A. Bhounsule, [email protected]
% Last updated: 18 May 2016
%
% For details about the model etc. see
% Schwind, William John. "Spring loaded inverted pendulum running:
% A plant model." PhD diss., 1998.
function slipHopper
clc
clear all
close all
format long
% %%% initial parameters (set 1)
% robot.g = 10;
% robot.ground = 0; %ground is at y co-ordinate equal to robot.ground
% robot.l = 1;
% robot.m = 100;
% robot.control.k = 10000;
% robot.control.theta = 5*(pi/180); %pi/6; %angle between leg and vertical
% x0dot = 0.50435 ;% 0.5;
% y0 = 1.1873 ;
% %Root finding will give this root
% %zstar = [0.513806075894484 1.238312718076982];
%%%% initial parameters (set 2)
robot.g = 10;
robot.ground = 0; %ground is at y co-ordinate equal to robot.ground
robot.l = 1;
robot.m = 1;
robot.control.k = 100;
robot.control.theta = 10*(pi/180); %angle between leg and vertical
x0dot = 1;
y0 = 1.2;
% % Root finding will give this unstable root
% % zstar = [1.017450873821607 1.182441943200824];
% initial guess
z0 = [x0dot y0];
% %%%%%%%%%%%%%%%%%%%%%%%%%
steps = 5; %number of steps to animate
fps = 30; %Use low frames per second for low gravity
%%% Root finding, Period one gait %%%%
options = optimset('TolFun',1e-10,'TolX',1e-10,'Display','iter');
[zstar,fval,exitflag] = fsolve(@fixedpt,z0,options,robot);
if exitflag == 1
disp('Fixed point:');
disp(zstar);
else
error('Root finder not converged, change guess or change system parameters')
end
%%% Stability, using eigenvalues of Poincare map %%%
J=partialder(@onestep,zstar,robot)
disp('EigenValues for linearized map are');
eig(J)
%%%% Get data for all the steps %%%
[z,t] = onestep(zstar,robot,steps);
% %%% Animate result %%%
disp('Animating...');
animate(t,z,robot,steps,fps);
%%% Plot data %%%
disp('Some plots...')
figure(2)
subplot(2,1,1)
plot(t,z(:,1),'r',t,z(:,3),'b')
xlabel('time'); ylabel('Angle (m)');
legend('x','y');
subplot(2,1,2)
plot(t,z(:,2),'r',t,z(:,4),'b')
xlabel('time'); ylabel('Velocity (m/s)');
legend('vx','vy');
figure(3)
plot(z(:,1),z(:,3),'r'); %hold on
xlabel('x'); ylabel('y');
title('Trajectory y vs x');
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%%%% FUNCTIONS START HERE %%%%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%===================================================================
function zdiff=fixedpt(z0,robot)
%===================================================================
zdiff=onestep(z0,robot)-z0;
%===================================================================
function J=partialder(FUN,z,robot)
%===================================================================
pert=1e-5;
n = length(z);
J = zeros(n,n);
%%%% Using forward difference, accuracy linear %%%
% y0=feval(FUN,z,walker);
% for i=1:n
% ztemp=z;
% ztemp(i)=ztemp(i)+pert;
% J(:,i)=(feval(FUN,ztemp,walker)-y0) ;
% end
% J=(J/pert);
%%% Using central difference, accuracy quadratic %%%
for i=1:n
ztemp1=z; ztemp2=z;
ztemp1(i)=ztemp1(i)+pert;
ztemp2(i)=ztemp2(i)-pert;
J(:,i)=(feval(FUN,ztemp1,robot)-feval(FUN,ztemp2,robot)) ;
end
J=J/(2*pert);
%===================================================================
function [z,t]=onestep(z0,robot,steps) %DONE
%===================================================================
flag = 1;
if nargin<2
error('need more inputs to onestep');
elseif nargin<3
flag = 0; %send only last state, for root finder and jacobian
steps = 1;
end
x0 = 0; x0dot = z0(1);
y0 = z0(2); y0dot = 0;
z0 = [x0 x0dot y0 y0dot];
t0 = 0;
dt = 5; %might need to be changed based on time taken for one step
time_stamps = 100;
t_ode = t0;
z_ode = [z0 ...
x0+robot.l*sin(robot.control.theta) ...
y0-robot.l*cos(robot.control.theta)];
for i=1:steps
%%% apex to ground %%%
options1 = odeset('Abstol',1e-13,'Reltol',1e-13,'Events',@contact);
tspan = linspace(t0,t0+dt,time_stamps);
[t_temp1,z_temp1]=ode113(@flight,tspan,z0,options1,robot);
z_temp1 = [z_temp1 ...
z_temp1(1:end,1)+robot.l*sin(robot.control.theta) ...
z_temp1(1:end,3)-robot.l*cos(robot.control.theta) ...
];
t0 = t_temp1(end);
z0(1:4) = z_temp1(end,1:4);
x_com = z0(1); %save the x position for future
z0(1) = -robot.l*sin(robot.control.theta); %relative distance wrt contact point because of non-holonomic nature of the system
x_foot = x_com + robot.l*sin(robot.control.theta);
y_foot = robot.ground;
%%% stance phase %%%
tspan = linspace(t0,t0+dt,time_stamps*10);
options2 = odeset('Abstol',1e-13,'Reltol',1e-13,'Events',@release);
[t_temp2,z_temp2]=ode113(@stance,tspan,z0,options2,robot);
z_temp2(:,1) = z_temp2(:,1) + x_com + robot.l*sin(robot.control.theta); %absolute x co-ordinate
z_temp2 = [z_temp2, ...
x_foot*ones(length(z_temp2),1) y_foot*ones(length(z_temp2),1)]; %the distal end of leg is 0 when touching the ground.
t0 = t_temp2(end);
z0(1:4) = z_temp2(end,1:4);
%%% ground to apex
tspan = linspace(t0,t0+dt,time_stamps);
options3 = odeset('Abstol',1e-13,'Reltol',1e-13,'Events',@apex);
[t_temp3,z_temp3]=ode113(@flight,tspan,z0,options3,robot);
z_temp3 = [z_temp3 ...
z_temp3(1:end,1)+robot.l*sin(robot.control.theta) ...
z_temp3(1:end,3)-robot.l*cos(robot.control.theta) ...
];
t0 = t_temp3(end);
z0(1:4) = z_temp3(end,1:4);
%%%%% Ignore time stamps for heelstrike and first integration point
t_ode = [t_ode; t_temp1(2:end); t_temp2(2:end); t_temp3(2:end)];
z_ode = [z_ode; z_temp1(2:end,:); z_temp2(2:end,:); z_temp3(2:end,:)];
end
z = [z0(2) z0(3)];
if flag==1
z=z_ode;
t=t_ode;
end
%===================================================================
function zdot=flight(t,z,robot)
%===================================================================
zdot = [z(2) 0 z(4) -robot.g]';
%===================================================================
function [gstop, isterminal,direction]=contact(t,z,robot)
%===================================================================
gstop = z(3) - robot.l*cos(robot.control.theta); %position is 0;
direction = -1; %negative direction goes from + to -
isterminal = 1; %1 is stop the integration
%===================================================================
function zdot=stance(t,z,robot)
%===================================================================
x = z(1); y = z(3); %x & y position of com wrt ground
l = sqrt(x^2+y^2);
F_spring = robot.control.k*(robot.l-l);
Fx_spring = F_spring*(x/l);
Fy_spring = F_spring*(y/l);
Fy_gravity = robot.m*robot.g;
xddot = (1/robot.m)*(Fx_spring);
yddot = (1/robot.m)*(-Fy_gravity+Fy_spring);
zdot = [z(2) xddot z(4) yddot]';
%===================================================================
function [gstop, isterminal,direction]=release(t,z,robot)
%===================================================================
l = sqrt(z(1)^2+z(3)^2);
gstop = l-robot.l;
direction = 1; %negative direction goes from + to -
isterminal = 1; %1 is stop the integration
%===================================================================
function [gstop, isterminal,direction]=apex(t,z,robot)
%===================================================================
gstop = z(4) - 0; %ydot is 0;
direction = 0; %negative direction goes from + to -
isterminal = 1; %1 is stop the integration
%===================================================================
function animate(t_all,z_all,robot,steps,fps)
%===================================================================
%%% interpolate for animation %%
[m,n] = size(z_all);
tinterp = linspace(t_all(1),t_all(end),fps*(t_all(end)-t_all(1)));
for i=1:n
z_interp(:,i) = interp1(t_all,z_all(:,i),tinterp);
end
[mm,nn] = size(z_interp);
min_xh = min(z_interp(:,1)); max_xh = max(z_interp(:,1));
dist_travelled = max_xh - min_xh;
camera_rate = dist_travelled/mm;
window_xmin = -1.0*robot.l; window_xmax = robot.l;
window_ymin = -0.1; window_ymax = 1.9*robot.l;
axis('equal')
axis([window_xmin window_xmax window_ymin window_ymax])
axis off
set(gcf,'Color',[1,1,1])
figure(1);
for i=1:length(tinterp)
plot(z_interp(i,1),z_interp(i,3),'ro','MarkerEdgeColor','r', 'MarkerFaceColor','r','MarkerSize',20); %com
line([-1 max(z_interp(:,1))+1],[0 0],'Linewidth',2,'Color','black'); %ground
line([z_interp(i,1) z_interp(i,5)],[z_interp(i,3) z_interp(i,6)],'Linewidth',4,'Color',[0 0.8 0]); %leg
window_xmin = window_xmin + camera_rate;
window_xmax = window_xmax + camera_rate;
axis('equal')
axis off
axis([window_xmin window_xmax window_ymin window_ymax])
pause(0.05);
end