Skip to content

Commit

Permalink
quieting warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake committed Mar 12, 2014
1 parent 6fe1e3b commit 0de4cf0
Show file tree
Hide file tree
Showing 11 changed files with 39 additions and 16 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ if (LCM_FOUND)

endif()

add_jar(drake ${drake_jar_javafiles})
add_jar(drake SOURCES ${drake_jar_javafiles})
install_jar(drake share/java)
pods_install_pkg_config_file(drake-java
CLASSPATH drake
Expand Down
2 changes: 1 addition & 1 deletion cmake
Submodule cmake updated 2 files
+10 −11 matlab_clean.pl
+2 −2 mex.cmake
6 changes: 0 additions & 6 deletions examples/PR2/pr2.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -1378,12 +1378,6 @@
<material value="Gazebo/White"/>
<turnGravityOff value="true"/>
</gazebo>
<gazebo reference="double_stereo_double_stereo_link">
<material value="PR2/Blue"/>
</gazebo>
<gazebo reference="sensor_mount_sensor_link">
<material value="PR2/Blue"/>
</gazebo>
<joint name="laser_tilt_mount_joint" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="0.65" lower="-0.7854" upper="1.48353" velocity="10.0"/>
Expand Down
9 changes: 6 additions & 3 deletions systems/plants/@RigidBodyManipulator/RigidBodyManipulator.m
Original file line number Diff line number Diff line change
Expand Up @@ -539,9 +539,10 @@
% end
end

function body_ind = findLinkInd(model,linkname,robot,throw_error)
function body_ind = findLinkInd(model,linkname,robot,error_level)
% @param robot can be the robot number or the name of a robot
% robot=0 means look at all robots
% @param error_level >0 for throw error, 0 for throw warning, <0 for do nothing. @default throw error
% @ingroup Kinematic Tree
if nargin<3 || isempty(robot), robot=0; end
linkname = lower(linkname);
Expand Down Expand Up @@ -569,11 +570,13 @@
end
end
if (length(ind)~=1)
if (nargin<4 || throw_error)
if (nargin<4 || error_level>0)
error(['couldn''t find unique link ' ,linkname]);
else
warning(['couldn''t find unique link ' ,linkname]);
body_ind=0;
if (error_level==0)
warning(['couldn''t find unique link ' ,linkname]);
end
end
else
body_ind = ind;
Expand Down
2 changes: 1 addition & 1 deletion systems/plants/@RigidBodyManipulator/addRobotFromURDF.m
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@
function model = parseGazebo(model,robotnum,node,options)
ref = char(node.getAttribute('reference'));
if ~isempty(ref)
body_ind = findLinkInd(model,ref,robotnum,false);
body_ind = findLinkInd(model,ref,robotnum,-1);
if body_ind>0
grav = node.getElementsByTagName('turnGravityOff').item(0);
if ~isempty(grav)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
function RelativeGazeTargetConstraintTest()
% Andres would update the RelativeGazeTargetConstraint
r = RigidBodyManipulator(strcat(getDrakePath(),'/examples/PR2/pr2.urdf'));
w = warning('off','Drake:RigidBody:SimplifiedCollisionGeometry');
warning('off','Drake:RigidBodyManipulator:UnsupportedVelocityLimits');
warning('off','Drake:RigidBodyManipulator:BodyHasZeroInertia');
r = RigidBodyManipulator(fullfile(getDrakePath(),'examples','PR2','pr2.urdf'));
warning(w);
q_nom = zeros(r.getNumDOF(),1);
constraintTester('RelativeGazeTargetConstraintTest', r, @makeCon, @(r) q_nom, @(r) q_nom, [],[],[],[],false);
end
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
function WorldPositionInFrameConstraintTest(varargin)
r = RigidBodyManipulator(strcat(getDrakePath(),'/examples/PR2/pr2.urdf'));
w = warning('off','Drake:RigidBody:SimplifiedCollisionGeometry');
warning('off','Drake:RigidBodyManipulator:UnsupportedVelocityLimits');
warning('off','Drake:RigidBodyManipulator:BodyHasZeroInertia');
r = RigidBodyManipulator(fullfile(getDrakePath(),'examples','PR2','pr2.urdf'));
warning(w);
q_nom = zeros(r.getNumDOF(),1);
constraintTester('WorldPositionInFrameConstraintTest', r, @makeCon, @(r) q_nom, @(r) q_nom, 10, varargin{:});
end
Expand Down
4 changes: 4 additions & 0 deletions systems/plants/test/testApproximateIK.m
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,11 @@ function testApproximateIK()
options.floating = true;
options.dt = 0.001;
urdf = fullfile(getDrakePath,'examples','Atlas','urdf','atlas_minimal_contact.urdf');
w = warning('off','Drake:RigidBodyManipulator:UnsupportedVelocityLimits');
warning('off','Drake:RigidBodyManipulator:UnsupportedContactPoints');
warning('off','Drake:RigidBodyManipulator:UnsupportedJointLimits');
r = RigidBodyManipulator(urdf,options);
warning(w);
v = r.constructVisualizer();
nq = r.getNumDOF();
cost = Point(r.getStateFrame,1);
Expand Down
9 changes: 9 additions & 0 deletions systems/visualizers/NullVisualizer.m
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,15 @@
function status = draw(obj,t,x,flag)
status = 0;
end

function drawWrapper(obj,t,y)
% intentionally blank
end

function playback(obj,xtraj,options)
% intentionally blank
end

end
end

Expand Down
2 changes: 1 addition & 1 deletion systems/visualizers/Visualizer.m
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
end
end

function drawWrapper(obj,t,y);
function drawWrapper(obj,t,y)
sfigure(obj.fignum);
clf; hold on;
draw(obj,t,y);
Expand Down
7 changes: 6 additions & 1 deletion util/checkDependency.m
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,7 @@
end

case 'vrml'
unsupported = false;
if(exist('vrinstall','file'))
conf.vrml_enabled = logical(vrinstall('-check','-viewer'));% && usejava('awt'); % usejava('awt') return 0 if running with no display
if ismac
Expand All @@ -113,13 +114,17 @@
% per my support ticket to matlab, who sent a perfunctory response
% pointing to this: http://www.mathworks.com/support/sysreq/release2012a/macintosh.html
conf.vrml_enabled = false;
disp(' ');
disp(' Found Simulink 3D Animation Toolbox, but is not supported in this version of MATLAB. See http://www.mathworks.com/support/sysreq/release2012a/macintosh.html ');
disp(' ');
unsupported = true;
end
end
else
conf.vrml_enabled=false;
end

if (~conf.vrml_enabled)
if (~conf.vrml_enabled && ~unsupported)
disp(' ');
disp(' Simulink 3D Animation Toolbox not found. Have you run ''vrinstall -install viewer''?');
disp(' ');
Expand Down

0 comments on commit 0de4cf0

Please sign in to comment.