Skip to content

Commit

Permalink
resolves bug 1153 - bouncing ball code needs frame specifications
Browse files Browse the repository at this point in the history
minor fixes in export to movie code.

git-svn-id: https://svn.csail.mit.edu/locomotion/robotlib/trunk@3746 c9849af7-e679-4ec6-a44e-fc146a885bd3
  • Loading branch information
russt committed Sep 8, 2012
1 parent a5f5ab8 commit 71a67c6
Show file tree
Hide file tree
Showing 6 changed files with 107 additions and 3 deletions.
2 changes: 2 additions & 0 deletions examples/BouncingBall/BallPlant.m
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@

% create flight mode system
sys = BallFlightPhasePlant();
obj = setInputFrame(obj,sys.getInputFrame);
obj = setOutputFrame(obj,sys.getOutputFrame);
[obj,flight_mode] = addMode(obj,sys); % add the single mode

g1=inline('x(1)-obj.r','obj','t','x','u'); % q-r<=0
Expand Down
28 changes: 28 additions & 0 deletions examples/dev/mass_spring_damper/MassSpringDamperPlant.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
classdef MassSpringDamperPlant < SecondOrderSystem
% Defines the dynamics for the Pendulum.

properties
m = 1; % kg
b = .5;
k = 20;
end

methods
function obj = MassSpringDamperPlant()
% Construct a new PendulumPlant
obj = obj@SecondOrderSystem(1,1,true);
obj = setOutputFrame(obj,obj.getStateFrame);
end

function qdd = sodynamics(obj,t,q,qd,u)
% Implement the second-order dynamics
qdd = (u - obj.k*q - obj.b*qd)/obj.m;
end

function x = getInitialState(obj)
% Start me anywhere!
x = randn(2,1);
end
end

end
48 changes: 48 additions & 0 deletions examples/dev/mass_spring_damper/MassSpringDamperVisualizer.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
classdef MassSpringDamperVisualizer < Visualizer
% Implements the draw function for the Pendulum

% todo: use correct pendulum parameters (possibly acquire them via a
% constructor?)

methods
function obj = MassSpringDamperVisualizer(r)
obj = obj@Visualizer(r.getStateFrame);
end

function draw(obj,t,x)
persistent hFig base wb lwheel rwheel spring dashpot;
if (isempty(hFig))
hFig = figure(25);
set(hFig,'DoubleBuffer', 'on');

theta = pi*[0:0.025:2];
wb = .3; hb=.2;
wheelr = 0.05;
lwheel = [-wb/2 + wheelr*cos(theta); wheelr + wheelr*sin(theta)]';
base = [wb*[1 -1 -1 1]; hb*[1 1 -1 -1]+hb+2*wheelr]';
spring = [ 0,linspace(.2,.8,length(theta)),1; [0,.1*sin(8*theta),0]+.3 ];
end

figure(hFig); cla; hold on; view(0,90);

x = x(1);
% draw the cart
patch(x(1)+base(:,1), base(:,2),0*base(:,1),'b','FaceColor',[.3 .6 .4])
patch(x(1)+lwheel(:,1), lwheel(:,2), 0*lwheel(:,1),'k');
patch(x(1)+wb+lwheel(:,1), lwheel(:,2), 0*lwheel(:,1),'k');

% draw the floor
line([-5,5],[0,0],'Color',.7*[1 1 1],'LineWidth',1.2);

% draw the wall
line([-1,-1],[0,1],'Color',.7*[1 1 1],'LineWidth',1.2);

% draw the spring
plot(-1+spring(1,:)*(x-wb+1),spring(2,:),'k');

axis equal;
axis([-1.5 1.5 -0.5 1]);
end
end

end
2 changes: 1 addition & 1 deletion systems/Visualizer.m
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ function playbackAVI(obj,xtraj,filename)
for i=1:length(tspan)
obj.draw(tspan(i),eval(xtraj,tspan(i)));
if (obj.display_time)
title(['t = ', num2str(t,'%.2f') ' sec']);
title(['t = ', num2str(tspan(i),'%.2f') ' sec']);
end
if (obj.draw_axes)
f=gcf;
Expand Down
2 changes: 1 addition & 1 deletion systems/trajectories/DTTrajectory.m
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
obj.tspan = [min(tt) max(tt)];
end
function y = eval(obj,t)
ind = find(obj.tt==t); % only return on exact matches. For interpolation, you should be using zoh or foh to make PPTrajectories
ind = find(abs(obj.tt-t)<1e-10); % only return on exact matches. For interpolation, you should be using zoh or foh to make PPTrajectories
y = obj.xx(:,ind);
end

Expand Down
28 changes: 27 additions & 1 deletion util/vCalWriter.m
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ function addEvent(obj,summary,startdatevec,enddatevec,description,location,rrule

if nargin>4 && ~isempty(description)
typecheck(description,'char');
fprintf(obj.fhandle,'LOCATION:%s\r\n',description);
fprintf(obj.fhandle,'DESCRIPTION:%s\r\n',description);
end

if nargin>5 && ~isempty(location)
Expand All @@ -83,6 +83,32 @@ function addEvent(obj,summary,startdatevec,enddatevec,description,location,rrule
fprintf(obj.fhandle,'END:VEVENT\r\n');
end

function addTodo(obj,summary,duedatevec,description,rrule)
if datenum(duedatevec)<obj.min_datenum || datenum(duedatevec)>obj.max_datenum
error('due date out of range. you may need to update the timezone implementation in the vCalWriter class');
end
fprintf(obj.fhandle,'BEGIN:VTODO\r\n');

typecheck(summary,'char');
fprintf(obj.fhandle,'SUMMARY:%s\r\n',summary);

sizecheck(duedatevec,6);
fprintf(obj.fhandle,'DUE;TZID=US-Eastern:%02d%02d%02dT%02d%02d%02d\r\n',duedatevec);

if nargin>4 && ~isempty(description)
typecheck(description,'char');
fprintf(obj.fhandle,'DESCRIPTION:%s\r\n',description);
end

if nargin>6 && ~isempty(rrule)
typecheck(rrule,'char');
fprintf(obj.fhandle,'RRULE:%s\r\n',rrule);
end

fprintf(obj.fhandle,'END:VTODO\r\n');
end


function delete(obj)
fprintf(obj.fhandle,'END:VCALENDAR\r\n');
fclose(obj.fhandle);
Expand Down

0 comments on commit 71a67c6

Please sign in to comment.