Skip to content

Commit

Permalink
make sure lqr examples can run even if sedumi is not installed.
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake committed Jan 28, 2014
1 parent e017dce commit 60f82da
Show file tree
Hide file tree
Showing 2 changed files with 71 additions and 56 deletions.
63 changes: 35 additions & 28 deletions examples/CartPole/runLQR.m
Original file line number Diff line number Diff line change
Expand Up @@ -3,36 +3,43 @@
d = CartPolePlant;
d = setInputLimits(d,-inf,inf);
v = CartPoleVisualizer(d);
[c,V] = balanceLQR(d);

sys = feedback(d,c);

x0 = [0;pi;0;0];
%for i=1:5
% xtraj=simulate(sys,[0 4],x0+.2*randn(4,1));
% v.playback(xtraj);
%end

V = V.inFrame(d.getStateFrame);

figure(1); plotFunnel(V,struct('plotdims',[2 4],'inclusion','projection'));
xlabel('$\theta$','interpreter','latex');
ylabel('$\dot\theta$','interpreter','latex');

% xa = [.02178;2.437;-.4347;3.091];
% keyboard;

n=5;
y=getLevelSet(V,[],struct('num_samples',n));
for i=1:n
xtraj=simulate(sys,[0 4],.01*x0 + .99*y(:,i));
figure(1); fnplt(xtraj,[2 4]);
figure(25);
v.playback(xtraj);
if (V.eval(4,xtraj.eval(4))>V.eval(0,xtraj.eval(0)))
xtraj.eval(4)-x0
error('simulation appears to be going uphill on the Lyapunov function');
if checkDependency('sedumi')
[c,V] = balanceLQR(d);
sys = feedback(d,c);
x0 = [0;pi;0;0];

V = V.inFrame(d.getStateFrame);

figure(1); plotFunnel(V,struct('plotdims',[2 4],'inclusion','projection'));
xlabel('$\theta$','interpreter','latex');
ylabel('$\dot\theta$','interpreter','latex');

% xa = [.02178;2.437;-.4347;3.091];
% keyboard;

n=5;
y=getLevelSet(V,[],struct('num_samples',n));
for i=1:n
xtraj=simulate(sys,[0 4],.01*x0 + .99*y(:,i));
figure(1); fnplt(xtraj,[2 4]);
figure(25);
v.playback(xtraj);
if (V.eval(4,xtraj.eval(4))>V.eval(0,xtraj.eval(0)))
xtraj.eval(4)-x0
error('simulation appears to be going uphill on the Lyapunov function');
end
end
else
c = balanceLQR(d);
sys = feedback(d,c);
x0 = [0;pi;0;0];

for i=1:5
xtraj=simulate(sys,[0 4],x0+.2*randn(4,1));
v.playback(xtraj);
end
end


end
64 changes: 36 additions & 28 deletions examples/Quadrotor2D/runLQR.m
Original file line number Diff line number Diff line change
Expand Up @@ -3,35 +3,43 @@
p = PlanarQuadPlant;
v = PlanarQuadVisualizer(p);

[c,V] = hoverLQR(p);

sys = feedback(p,c);
%for i=1:5
% xtraj = simulate(sys,[0 4]);
% v.playback(xtraj);
%end
%return;

figure(1); plotFunnel(V,struct('plotdims',[3 6]));
xlabel('$\theta$','interpreter','latex');
ylabel('$\dot\theta$','interpreter','latex');


n=5;
x0=zeros(6,1);
y=getLevelSet(V,[],struct('num_samples',n));
for i=1:n
xtraj=simulate(sys,[0 4],x0 + .99*y(:,i));
figure(1); fnplt(xtraj,[3 6]);
figure(25);
v.playback(xtraj);
if checkDependency('sedumi')
[c,V] = hoverLQR(p);
sys = feedback(p,c);

figure(1); plotFunnel(V,struct('plotdims',[3 6]));
xlabel('$\theta$','interpreter','latex');
ylabel('$\dot\theta$','interpreter','latex');


ts = xtraj.getBreaks();Vs=zeros(1,length(ts));
for i=1:length(ts)
Vs(i) = V.eval(ts(i),xtraj.eval(ts(i)));
n=5;
x0=zeros(6,1);
y=getLevelSet(V,[],struct('num_samples',n));
for i=1:n
xtraj=simulate(sys,[0 4],x0 + .99*y(:,i));
figure(1); fnplt(xtraj,[3 6]);
figure(25);
v.playback(xtraj);

ts = xtraj.getBreaks();Vs=zeros(1,length(ts));
for i=1:length(ts)
Vs(i) = V.eval(ts(i),xtraj.eval(ts(i)));
end
if any(diff(Vs)>1e-4)
diff(Vs)
error('V(t,x) increased at some point in the trajectory from an initial condition in the verified ROA.');
end
end
if any(diff(Vs)>1e-4)
diff(Vs)
error('V(t,x) increased at some point in the trajectory from an initial condition in the verified ROA.');

else
c = hoverLQR(p);
sys = feedback(p,c);

for i=1:5
xtraj = simulate(sys,[0 4]);
v.playback(xtraj);
end

end


0 comments on commit 60f82da

Please sign in to comment.