Skip to content

Commit

Permalink
Adding the tests that require 3D Simulink Animation to NOTEST for Dra…
Browse files Browse the repository at this point in the history
…ke build server.

git-svn-id: https://svn.csail.mit.edu/locomotion/robotlib/trunk@6231 c9849af7-e679-4ec6-a44e-fc146a885bd3
  • Loading branch information
mjp committed Jun 4, 2013
1 parent 81bb483 commit 88c3975
Show file tree
Hide file tree
Showing 22 changed files with 32 additions and 22 deletions.
1 change: 1 addition & 0 deletions examples/Atlas/runAtlasDynamics.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function runAtlasDynamics
% NOTEST
% just runs it as a passive system

% just runs it as a passive system for now
Expand Down
2 changes: 1 addition & 1 deletion examples/Atlas/runCOMFixedPointSearch.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function [xstar,ustar,zstar] = runCOMFixedPointSearch()

% NOTEST
planar = false;
runsim = false; % run 1s sim with constant input after search

Expand Down
1 change: 1 addition & 0 deletions examples/Atlas/runPD.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function runPD()
% NOTEST

options.floating = true;
options.dt = 0.001;
Expand Down
4 changes: 2 additions & 2 deletions examples/Atlas/runReachingDemo.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function runReachingDemo

% NOTEST
options.floating = true;
options.dt = 0.001;
r = Atlas('urdf/atlas_minimal_contact.urdf',options);
Expand Down Expand Up @@ -132,4 +132,4 @@
traj = simulate(sys,[0 T]);
playback(v,traj,struct('slider',true));

end
end
4 changes: 2 additions & 2 deletions examples/Atlas/runStandingDemo.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function runStandingDemo

% NOTEST
options.floating = true;
options.dt = 0.001;
r = Atlas('urdf/atlas_minimal_contact.urdf',options);
Expand Down Expand Up @@ -85,4 +85,4 @@
playback(v,traj,struct('slider',true));


end
end
2 changes: 1 addition & 1 deletion examples/Atlas/runWalkDemo.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function runWalkDemo(num_steps,step_length,step_time)

% NOTEST
if (nargin<1) num_steps = 8; end
if (nargin<2) step_length = 0.4; end
if (nargin<3) step_time = 1; end
Expand Down
2 changes: 1 addition & 1 deletion examples/Atlas/test/testApproximateIK.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function testApproximateIK

% NOTEST
addpath('..');
options.floating = true;
options.dt = 0.001;
Expand Down
2 changes: 1 addition & 1 deletion examples/Atlas/test/testIK.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function testIK

% NOTEST
addpath('..');
options.floating = true;
options.dt = 0.001;
Expand Down
3 changes: 2 additions & 1 deletion examples/Atlas/test/testIKsequence.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function [qtraj,info] = testIKsequence(qtraj0)
% NOTEST
options.floating = true;
options.dt = 0.001;
oldpath = addpath(fullfile(pwd,'..'));
Expand Down Expand Up @@ -79,4 +80,4 @@
v = p.constructVisualizer();
v.playback(xtraj,struct('slider',true));

end
end
1 change: 1 addition & 0 deletions examples/FurutaPendulum/runLQR.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function runLQR
% NOTEST

p = RigidBodyManipulator('FurutaPendulum.urdf');

Expand Down
2 changes: 1 addition & 1 deletion examples/PR2/drawPR2.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function drawPR2

% NOTEST
r = RigidBodyManipulator('pr2.urdf');

if checkDependency('vrml_enabled')
Expand Down
1 change: 1 addition & 0 deletions examples/PR2/runPassive.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function runPassive
% NOTEST

r = RigidBodyManipulator('pr2.urdf');
r = setSimulinkParam(r,'MinStep','0.001');
Expand Down
4 changes: 2 additions & 2 deletions examples/Pendulum/runPassiveWRL.m
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
function runPassiveWRL

% NOTEST
p = PlanarRigidBodyManipulator('Pendulum.urdf');
x = p.simulate([0 5],randn(2,1));

if (checkDependency('vrml_enabled'))
v = RigidBodyWRLVisualizer(p);
v.playback(x);
end
end
2 changes: 1 addition & 1 deletion examples/ZMP/CartTable.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
classdef CartTable < TimeSteppingRigidBodyManipulator

% NOTEST
methods
function obj = CartTable()
obj = obj@TimeSteppingRigidBodyManipulator('CartTable.urdf',0.005,struct('floating',true));
Expand Down
3 changes: 3 additions & 0 deletions make.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
function make(varargin)

% If we are UNIX, use the GNU makefile instead


% Builds all mex files in the directory

flags = {'-O'};
Expand Down
4 changes: 2 additions & 2 deletions systems/plants/test/bullet_collision_jac_test.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function bullet_collision_jac_test

% NOTEST
r = RigidBodyManipulator();

for i=1:2
Expand Down Expand Up @@ -40,4 +40,4 @@
end
end

end
end
4 changes: 2 additions & 2 deletions systems/plants/test/bullet_collision_normals_test.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function bullet_collision_normals_test

% NOTEST
r = RigidBodyManipulator();
r = addRobotFromURDF(r,'FallingBrick.urdf',zeros(3,1),zeros(3,1),struct('floating',true));
r = addRobotFromURDF(r,'ground_plane.urdf',zeros(3,1),zeros(3,1),struct('floating',false));
Expand Down Expand Up @@ -30,4 +30,4 @@
valuecheck(n,n2(phi2<1e-8,:),1e-5);
end

end
end
4 changes: 2 additions & 2 deletions systems/plants/test/doublePendWBiceptSpring.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function doublePendWBiceptSpring

% NOTEST
r = RigidBodyManipulator('DoublePendWBiceptSpring.urdf');
x0 = [0;pi;0;0]+.1*randn(4,1);
run_time = 10;
Expand All @@ -13,4 +13,4 @@

end

% NORELEASE
% NORELEASE
4 changes: 2 additions & 2 deletions systems/plants/test/fallingBrickLCP.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function fallingBrickLCP

% NOTEST
options.floating = true;
p = TimeSteppingRigidBodyManipulator('FallingBrick.urdf',.01,options);
x0 = p.resolveConstraints([0;1+rand;randn(10,1)]);
Expand All @@ -24,4 +24,4 @@
phi
error('penetration');
end
end
end
2 changes: 1 addition & 1 deletion systems/plants/test/springPendulum.m
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
function springPendulum

% NOTEST
r = RigidBodyManipulator('SpringPendulum.urdf');
x0 = [-pi/2;0];
run_time = 10;
Expand Down
1 change: 1 addition & 0 deletions systems/plants/test/terrainInterpTest.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function terrainInterpTest
% NOTEST

[X,Y] = meshgrid(linspace(-9,9,31),linspace(-9,9,31));
r = TimeSteppingRigidBodyManipulator('FallingBrick.urdf',.01,struct('floating',true));
Expand Down
1 change: 1 addition & 0 deletions systems/plants/test/terrainTest.m
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
function terrainTest
% NOTEST

r = TimeSteppingRigidBodyManipulator('FallingBrick.urdf',.01,struct('floating',true));
r = setTerrain(r,RigidBodyHeightMapTerrain('terrainTest.png',[-10;10;0],[40,40,10]));
Expand Down

0 comments on commit 88c3975

Please sign in to comment.