Skip to content

Commit

Permalink
resolves RobotLocomotion#18 . woohoo!
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake committed Sep 26, 2015
1 parent 1cad006 commit dfd8bdc
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 3 deletions.
4 changes: 3 additions & 1 deletion drake/examples/Quadrotor/test/testCollisions.m
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,9 @@
x0 = Point(getStateFrame(r)); % initial conditions: all-zeros
x0.base_y = -1.5;
x0.base_z = .8;
x0.base_ydot = 5;
x0.base_qw = 1;
x0.base_vy = 5;
x0 = resolveConstraints(r,x0);
u0 = double(nominalThrust(r));

v = constructVisualizer(r);%,struct('use_collision_geometry',true));
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/ZMP/CartTable.m
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

methods
function obj = CartTable()
obj = obj@TimeSteppingRigidBodyManipulator('CartTable.urdf',0.005,struct('floating',true,'terrain',RigidBodyFlatTerrain()));
obj = obj@TimeSteppingRigidBodyManipulator('CartTable.urdf',0.005,struct('floating','quat','terrain',RigidBodyFlatTerrain()));

% obj = addSensor(obj,FullStateFeedbackSensor());
% obj = addSensor(obj,ContactForceTorqueSensor(obj,'base',[0;0],0);
Expand All @@ -12,7 +12,7 @@
methods (Static = true)
function run
r = CartTable;
xtraj = simulate(r,[0 7],[0;0;.12;0;.06;0;-.03;0;0;0;0;0;0;0;0;0]);
xtraj = simulate(r,[0 7],[0;0;.12;1;0;.06;0;-.03;0;0;0;0;0;0;0;0;0]);
v = r.constructVisualizer;
v.playback(xtraj,struct('slider',true));
end
Expand Down

0 comments on commit dfd8bdc

Please sign in to comment.