From e1117b5ae30c2d0eb09fc5c513d4daed68d7bd47 Mon Sep 17 00:00:00 2001 From: Jamie Snape Date: Wed, 28 Jun 2017 08:46:31 -0400 Subject: [PATCH] Remove unused MATLAB-only external dependencies --- .gitmodules | 24 ------ CMakeLists.txt | 39 --------- cmake/options.cmake | 39 --------- cmake/packages.cmake | 3 - drake/addpath_drake.m | 15 ---- drake/matlab/CMakeLists.txt | 37 -------- drake/matlab/util/CMakeLists.txt | 46 ---------- drake/matlab/util/checkDependency.m | 102 ---------------------- drake/matlab/util/debugMexEval.m | 95 --------------------- drake/matlab/util/dev/debugMexTest.cpp | 25 ------ drake/matlab/util/dev/debugMexTester.m | 10 --- drake/matlab/util/drakeDebugMex.cpp | 113 ------------------------- drake/matlab/util/test/CMakeLists.txt | 6 -- externals/avl | 1 - externals/iris | 1 - externals/meshconverters | 1 - externals/sedumi | 1 - externals/signalscope | 1 - externals/spotless | 1 - externals/xfoil | 1 - externals/yalmip | 1 - 21 files changed, 562 deletions(-) delete mode 100644 drake/matlab/util/debugMexEval.m delete mode 100644 drake/matlab/util/dev/debugMexTest.cpp delete mode 100644 drake/matlab/util/dev/debugMexTester.m delete mode 100644 drake/matlab/util/drakeDebugMex.cpp delete mode 160000 externals/avl delete mode 160000 externals/iris delete mode 160000 externals/meshconverters delete mode 160000 externals/sedumi delete mode 160000 externals/signalscope delete mode 160000 externals/spotless delete mode 160000 externals/xfoil delete mode 160000 externals/yalmip diff --git a/.gitmodules b/.gitmodules index f3107732405d..2eae226037e5 100644 --- a/.gitmodules +++ b/.gitmodules @@ -13,15 +13,9 @@ [submodule "externals/libbot"] path = externals/libbot url = https://github.com/RobotLocomotion/libbot2.git -[submodule "externals/spotless"] - path = externals/spotless - url = https://github.com/RobotLocomotion/spotless-pod.git [submodule "externals/director"] path = externals/director url = https://github.com/RobotLocomotion/director.git -[submodule "externals/signalscope"] - path = externals/signalscope - url = https://github.com/mitdrc/signal-scope.git [submodule "externals/octomap"] path = externals/octomap url = https://github.com/OctoMap/octomap.git @@ -34,24 +28,6 @@ [submodule "externals/mosek"] path = externals/mosek url = https://github.com/RobotLocomotion/mosek.git -[submodule "externals/iris"] - path = externals/iris - url = https://github.com/rdeits/iris-distro.git -[submodule "externals/yalmip"] - path = externals/yalmip - url = https://github.com/RobotLocomotion/yalmip.git -[submodule "externals/sedumi"] - path = externals/sedumi - url = https://github.com/RobotLocomotion/sedumi.git -[submodule "externals/avl"] - path = externals/avl - url = https://github.com/RobotLocomotion/avl.git -[submodule "externals/xfoil"] - path = externals/xfoil - url = https://github.com/RobotLocomotion/xfoil.git -[submodule "externals/meshconverters"] - path = externals/meshconverters - url = https://github.com/RobotLocomotion/meshConverters.git [submodule "externals/yaml_cpp"] path = externals/yaml_cpp url = https://github.com/jbeder/yaml-cpp.git diff --git a/CMakeLists.txt b/CMakeLists.txt index 44b013387e47..2dfc773a22fe 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,13 +20,7 @@ drake_setup_options() # BEGIN external projects # External projects in order of dependencies; 'trivial' ones first -drake_add_external(avl PUBLIC CMAKE FORTRAN) -drake_add_external(meshconverters PUBLIC CMAKE) drake_add_external(qt_property_browser CMAKE QT) -drake_add_external(sedumi PUBLIC CMAKE MATLAB) -drake_add_external(spotless PUBLIC CMAKE MATLAB) -drake_add_external(xfoil PUBLIC CMAKE FORTRAN) -drake_add_external(yalmip PUBLIC CMAKE MATLAB) # eigen # N.B. See #5785; do your best not to have to bump this to a newer commit. @@ -210,20 +204,6 @@ drake_add_external(yaml_cpp PUBLIC CMAKE drake_add_external(ctk_python_console CMAKE PYTHON QT DEPENDS pythonqt) -# iris -drake_add_external(iris PUBLIC CMAKE MATLAB PYTHON - CMAKE_ARGS - -DBUILD_TESTING=OFF - -DIRIS_WITH_CDD=ON - -DIRIS_WITH_EIGEN=OFF - -DIRIS_WITH_MATLAB=${Matlab_FOUND} - -DIRIS_WITH_MOSEK=OFF - -DIRIS_WITH_PYBIND11=OFF - -DPYTHON_EXECUTABLE=${PYTHON_EXECUTABLE} - -DPYTHON_INCLUDE_DIR=${PYTHON_INCLUDE_DIR} - -DPYTHON_LIBRARY=${PYTHON_LIBRARY} - DEPENDS eigen mosek pybind11) - # ignition_math drake_add_external(ignition_math PUBLIC CMAKE URL https://bitbucket.org/ignitionrobotics/ign-math/get/ignition-math3_3.2.0.tar.gz @@ -264,10 +244,6 @@ drake_add_external(bot_core_lcmtypes PUBLIC CMAKE PYTHON drake_add_external(robotlocomotion_lcmtypes PUBLIC CMAKE PYTHON DEPENDS bot_core_lcmtypes lcm) -# signalscope -drake_add_external(signalscope PUBLIC CMAKE PYTHON QT - DEPENDS ctk_python_console lcm pythonqt) - # Option to skip building drake proper via the superbuild. This allows the # superbuild to build everything BUT drake, which can still be built separately # from its build directory. This is used by the dashboards to make separate @@ -287,7 +263,6 @@ drake_add_external(drake LOCAL PUBLIC CMAKE ALWAYS MATLAB PYTHON VTK -DDISABLE_MATLAB:BOOL=${DISABLE_MATLAB} -DDISABLE_PYTHON:BOOL=${DISABLE_PYTHON} -DDISABLE_FORTRAN:BOOL=${DISABLE_FORTRAN} - -DWITH_AVL:BOOL=${WITH_AVL} -DWITH_BOT_CORE_LCMTYPES:BOOL=${WITH_BOT_CORE_LCMTYPES} -DWITH_BULLET:BOOL=${WITH_BULLET} -DWITH_CCD:BOOL=${WITH_CCD} @@ -300,25 +275,18 @@ drake_add_external(drake LOCAL PUBLIC CMAKE ALWAYS MATLAB PYTHON VTK -DWITH_IGNITION_MATH3:BOOL=${WITH_IGNITION_MATH} # TODO(jamiesnape): Fix naming inconsistency -DWITH_IGNITION_RNDF0:BOOL=${WITH_IGNITION_RNDF} # TODO(jamiesnape): Fix naming inconsistency -DWITH_IPOPT:BOOL=${WITH_IPOPT} - -DWITH_IRIS:BOOL=${WITH_IRIS} -DWITH_LCM:BOOL=${WITH_LCM} -DWITH_LIBBOT:BOOL=${WITH_LIBBOT} - -DWITH_MESHCONVERTERS:BOOL=${WITH_MESHCONVERTERS} -DWITH_MOSEK:BOOL=${WITH_MOSEK} -DWITH_NLOPT:BOOL=${WITH_NLOPT} -DWITH_OCTOMAP:BOOL=${WITH_OCTOMAP} -DWITH_PROTOBUF:BOOL=${WITH_PROTOBUF} -DWITH_PYBIND11:BOOL=${WITH_PYBIND11} -DWITH_PYTHON_3:BOOL=${WITH_PYTHON_3} - -DWITH_SEDUMI:BOOL=${WITH_SEDUMI} - -DWITH_SIGNALSCOPE:BOOL=${WITH_SIGNALSCOPE} -DWITH_SNOPT:BOOL=${WITH_SNOPT} -DWITH_SPDLOG:BOOL=${WITH_SPDLOG} - -DWITH_SPOTLESS:BOOL=${WITH_SPOTLESS} -DWITH_TEXTBOOK:BOOL=${WITH_TEXTBOOK} -DWITH_TINYOBJLOADER:BOOL=${WITH_TINYOBJLOADER} - -DWITH_XFOIL:BOOL=${WITH_XFOIL} - -DWITH_YALMIP:BOOL=${WITH_YALMIP} -DWITH_YAML_CPP:BOOL=${WITH_YAML_CPP} -DUSE_CLANG_TIDY:BOOL=${USE_CLANG_TIDY} -DUSE_INCLUDE_WHAT_YOU_USE:BOOL=${USE_INCLUDE_WHAT_YOU_USE} @@ -326,7 +294,6 @@ drake_add_external(drake LOCAL PUBLIC CMAKE ALWAYS MATLAB PYTHON VTK -DUSE_SANITIZER:STRING=${USE_SANITIZER} -DUSE_VALGRIND:STRING=${USE_VALGRIND} DEPENDS - avl bot_core_lcmtypes bullet ccd @@ -340,25 +307,19 @@ drake_add_external(drake LOCAL PUBLIC CMAKE ALWAYS MATLAB PYTHON VTK ignition-math ignition-rndf ipopt - iris lcm libbot - meshconverters mosek nlopt octomap protobuf pybind11 robotlocomotion_lcmtypes - sedumi snopt spdlog - spotless textbook tinyobjloader vtk - xfoil - yalmip yaml_cpp ) diff --git a/cmake/options.cmake b/cmake/options.cmake index 5d1446c8e048..3f25d7dbf9b6 100644 --- a/cmake/options.cmake +++ b/cmake/options.cmake @@ -317,49 +317,14 @@ macro(drake_setup_options) # END external projects that are ON by default #~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - # BEGIN external projects that are only needed when MATLAB is in use - - # The following projects are default ON when MATLAB is present and enabled. - # Otherwise, they are hidden and default OFF. - drake_optional_external(SEDUMI ON - DEPENDS "NOT DISABLE_MATLAB\;Matlab_FOUND" - "semi-definite programming solver") - - drake_optional_external(SPOTLESS ON - DEPENDS "NOT DISABLE_MATLAB\;Matlab_FOUND" - "polynomial optimization front-end for MATLAB") - - # The following projects are default OFF when MATLAB is present and enabled. - # Otherwise, they are hidden and default OFF. Some of them may also be hidden - # on Windows regardless of the status of MATLAB. - drake_optional_external(YALMIP OFF - DEPENDS "NOT DISABLE_MATLAB\;Matlab_FOUND" - "free optimization front-end for MATLAB") - - # END external projects that are only needed when MATLAB is in use - #~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ # BEGIN external projects that are OFF by default - drake_optional_external(AVL OFF - DEPENDS "NOT DISABLE_FORTRAN" - "use w/ AVL to compute aerodynamic coefficients for airfoils") - drake_optional_external(GUROBI OFF "Convex/integer optimization solver\; free for academics") - drake_optional_external(IRIS OFF - DEPENDS "WITH_MOSEK" - "fast approximate convex segmentation") - - drake_optional_external(MESHCONVERTERS OFF - "uses vcglib to convert a few standard filetypes") - drake_optional_external(MOSEK OFF "Convex optimization solver\; free for academics") - drake_optional_external(SIGNALSCOPE OFF - "Live plotting tool for LCM messages") - drake_optional_external(SNOPT OFF "Sparse Non-linear Optimizer\;" "requires access to RobotLocomotion/snopt-pod") @@ -367,10 +332,6 @@ macro(drake_setup_options) drake_optional_external(TEXTBOOK OFF "The Underactuated Robotics textbook and its examples") - drake_optional_external(XFOIL OFF - DEPENDS "NOT DISABLE_FORTRAN" - "use w/ XFOIL to compute aerodynamic coefficients for airfoils") - # END external projects that are OFF by default #~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ # BEGIN indirectly optional external projects diff --git a/cmake/packages.cmake b/cmake/packages.cmake index aa8224318796..cae9ef9104b5 100644 --- a/cmake/packages.cmake +++ b/cmake/packages.cmake @@ -156,7 +156,6 @@ macro(drake_find_packages) #~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ # BEGIN optional packages - drake_find_package(avl CONFIG) drake_find_package(bot2-core CONFIG) drake_find_package(bot2-lcmgl-client PKG_CONFIG) drake_find_package(Bullet MODULE) @@ -167,7 +166,6 @@ macro(drake_find_packages) drake_find_package(ignition-rndf0 CONFIG) drake_find_package(ipopt PKG_CONFIG) drake_find_package(lcm CONFIG) - drake_find_package(meshconverters CONFIG) drake_find_package(mosek CONFIG) drake_find_package(NLopt CONFIG) drake_find_package(octomap CONFIG) @@ -176,7 +174,6 @@ macro(drake_find_packages) drake_find_package(snopt CONFIG) drake_find_package(spdlog CONFIG) drake_find_package(VTK CONFIG) - drake_find_package(xfoil CONFIG) drake_find_package(yaml-cpp CONFIG) # END optional packages diff --git a/drake/addpath_drake.m b/drake/addpath_drake.m index 31dca5e053f0..711a1d5f61ba 100644 --- a/drake/addpath_drake.m +++ b/drake/addpath_drake.m @@ -25,21 +25,6 @@ end % add package directories to the matlab path -addpath(fullfile(root,'matlab','systems')); -addpath(fullfile(root,'matlab','systems','plants')); -addpath(fullfile(root,'matlab','systems','plants','collision')); -addpath(fullfile(root,'matlab','systems','plants','constraint')); -addpath(fullfile(root,'matlab','systems','controllers')); -addpath(fullfile(root,'matlab','systems','observers')); -addpath(fullfile(root,'matlab','systems','trajectories')); -addpath(fullfile(root,'matlab','systems','trajectories','TrajectoryLibraries')); -addpath(fullfile(root,'matlab','systems','trajectories','FunnelLibraries')); -addpath(fullfile(root,'matlab','systems','frames')); -addpath(fullfile(root,'matlab','systems','visualizers')); -addpath(fullfile(root,'matlab','systems','robotInterfaces')); -addpath(fullfile(root,'matlab','systems','robotInterfaces','calibration')); -addpath(fullfile(root,'matlab','solvers')); -addpath(fullfile(root,'matlab','solvers','trajectoryOptimization')); addpath(fullfile(root,'thirdParty')); addpath(fullfile(root,'thirdParty','bsd')); addpath(fullfile(root,'thirdParty','bsd','arrow3d')); diff --git a/drake/matlab/CMakeLists.txt b/drake/matlab/CMakeLists.txt index 207805af63f0..ae538fec0bd8 100644 --- a/drake/matlab/CMakeLists.txt +++ b/drake/matlab/CMakeLists.txt @@ -18,23 +18,6 @@ install(FILES "${CMAKE_CURRENT_BINARY_DIR}/drake_get_lib_path.m" DESTINATION matlab) -find_program(FFMPEG_EXECUTABLE NAMES ffmpeg avconv - DOC "Path to the ffmpeg executable") - -if(avl_FOUND) - # Needs to be in cache to keep MATLAB happy. AVL_EXECUTABLE is set by - # find_package(avl). - set(AVL_EXECUTABLE "${AVL_EXECUTABLE}" - CACHE FILEPATH "Path to the avl executable") -endif() - -if(xfoil_FOUND) - # Needs to be in cache to keep MATLAB happy. XFOIL_EXECUTABLE is set by - # find_package(xfoil). - set(XFOIL_EXECUTABLE "${XFOIL_EXECUTABLE}" - CACHE FILEPATH "Path to the xfoil executable") -endif() - if(lcm_FOUND) # Needs to be in cache to keep MATLAB happy. The target lcm-java is imported # by find_package(lcm). @@ -52,10 +35,7 @@ if(BUILD_TESTING) drake_add_matlab_addpath_test(gurobi) drake_add_matlab_addpath_test(mosek) - drake_add_matlab_addpath_test(sedumi) drake_add_matlab_addpath_test(snopt) - drake_add_matlab_addpath_test(spotless) - drake_add_matlab_addpath_test(yalmip) function(drake_add_matlab_check_dependency_test dependency) drake_add_matlab_test(NAME matlab/check_dependency_${dependency} @@ -63,16 +43,11 @@ if(BUILD_TESTING) CHECK_DEPENDENCY_STRICT SIZE small) endfunction() - drake_add_matlab_check_dependency_test(avl) drake_add_matlab_check_dependency_test(bullet) drake_add_matlab_check_dependency_test(gurobi) - drake_add_matlab_check_dependency_test(iris) drake_add_matlab_check_dependency_test(lcm) drake_add_matlab_check_dependency_test(mosek) - drake_add_matlab_check_dependency_test(sedumi) drake_add_matlab_check_dependency_test(snopt) - drake_add_matlab_check_dependency_test(spotless) - drake_add_matlab_check_dependency_test(xfoil) # Unknown dependency. drake_add_matlab_test(NAME matlab/check_dependency_unknown @@ -91,12 +66,10 @@ if(BUILD_TESTING) # TODO(jamiesnape): These would still pass if MATLAB fails for a reason # other than a missing dependency. - drake_add_matlab_check_dependency_test_no(avl) drake_add_matlab_check_dependency_test_no(gurobi) drake_add_matlab_check_dependency_test_no(lcm) drake_add_matlab_check_dependency_test_no(mosek) drake_add_matlab_check_dependency_test_no(snopt) - drake_add_matlab_check_dependency_test_no(xfoil) if(NOT Bullet_FOUND) drake_add_matlab_test(NAME matlab/check_dependency_no_bullet @@ -105,16 +78,6 @@ if(BUILD_TESTING) PROPERTIES WILL_FAIL ON) endif() - if(FFMPEG_EXECUTABLE) - drake_add_matlab_test(NAME matlab/check_dependency_ffmpeg - COMMAND "checkDependency('ffmpeg')" CHECK_DEPENDENCY_STRICT SIZE small) - else() - drake_add_matlab_test(NAME matlab/check_dependency_no_ffmpeg - COMMAND "checkDependency('ffmpeg')" CHECK_DEPENDENCY_STRICT SIZE small) - set_tests_properties(matlab/check_dependency_no_ffmpeg - PROPERTIES WILL_FAIL ON) - endif() - if(Matlab_SIMULINK_FOUND) drake_add_matlab_test(NAME matlab/check_dependency_simulink COMMAND "checkDependency('simulink')" CHECK_DEPENDENCY_STRICT diff --git a/drake/matlab/util/CMakeLists.txt b/drake/matlab/util/CMakeLists.txt index fd2281fd8405..2d2eaf5e032e 100644 --- a/drake/matlab/util/CMakeLists.txt +++ b/drake/matlab/util/CMakeLists.txt @@ -52,52 +52,6 @@ if(Matlab_FOUND) endif() endif() -# Mex debugging tools: -if(0) - drake_add_mex(drake_debug_mex EXECUTABLE drakeDebugMex.cpp) - target_link_libraries(drake_debug_mex drakeMexUtil) - - message(STATUS "Writing drake_debug_mex.sh") - file(WRITE ${CMAKE_BINARY_DIR}/bin/drake_debug_mex.sh - "#!/bin/bash\n" - "\n" - "# Usage:\n" - "# % drake_debug_mex.sh [args]\n" - "# will set up the environment and then run:\n" - "# % args drake-debug-mex\n" - "#\n" - "# For example,\n" - "# % drake_debug_mex.sh\n" - "# will simply run the executable,\n" - "# % drake_debug_mex.sh gdb\n" - "# will run gdb on drake-debug-mex, and\n" - "# % drake_debug_mex.sh valgrind --leak-check=full --dsymutil=yes --track-origins=yes --xml=yes\n" - "# will run valgrind with the appropriate arguments passed in.\n" - "#\n" - "# It's not pretty, but seems to work for the use\n" - "# cases I've imagined so far. - RussT\n" - "\n") - - if(APPLE) - file(APPEND ${CMAKE_BINARY_DIR}/bin/drake_debug_mex.sh - "export DYLD_LIBRARY_PATH=$DYLD_LIBRARY_PATH:${MATLAB_ROOT}/bin/${MATLAB_CPU}\n" - "export DYLD_FORCE_FLAT_NAMESPACE=1\n" - "export DYLD_INSERT_LIBRARIES=${CMAKE_BINARY_DIR}/lib/libdebugMex.dylib\n") - else() - file(APPEND ${CMAKE_BINARY_DIR}/bin/drake_debug_mex.sh - "export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:${MATLAB_ROOT}/bin/${MATLAB_CPU}\n" - "export LD_PRELOAD=${CMAKE_BINARY_DIR}/lib/libdebugMex.so\n") - endif() - - file(APPEND ${CMAKE_BINARY_DIR}/bin/drake_debug_mex.sh - "\n" - "\"\$@\" ${CMAKE_BINARY_DIR}/bin/drake_debug_mex\n") - - install(FILES ${CMAKE_BINARY_DIR}/bin/drake_debug_mex.sh - DESTINATION ${CMAKE_INSTALL_PREFIX}/bin - PERMISSIONS OWNER_READ OWNER_EXECUTE GROUP_READ GROUP_EXECUTE WORLD_READ WORLD_EXECUTE) -endif() - add_subdirectory(geometry/test) if(BUILD_TESTING) diff --git a/drake/matlab/util/checkDependency.m b/drake/matlab/util/checkDependency.m index a036056ef6ad..55ad0a75c704 100644 --- a/drake/matlab/util/checkDependency.m +++ b/drake/matlab/util/checkDependency.m @@ -54,19 +54,6 @@ matlabpool; end - case 'spotless' - conf.spotless_enabled = logical(exist('msspoly','class')); - if ~conf.spotless_enabled - if ~pod_pkg_config('spotless') && nargout<1 - disp(' '); - disp(' SPOTLESS not found. spotless support will be disabled.'); - disp(' To re-enable, install spotless using drake''s cmake option WITH_SPOTLESS=ON'); - disp(' Or install it directly from https://github.com/spot-toolbox/spotless and add it to your path'); - disp(' '); - end - conf.spotless_enabled = logical(exist('msspoly','class')); - end - case 'lcm' conf.lcm_enabled = logical(exist('lcm.lcm.LCM','class')); if (~conf.lcm_enabled) @@ -188,28 +175,6 @@ disp(' '); end - case 'sedumi' - conf.sedumi_enabled = logical(exist('sedumi','file')); - if (~conf.sedumi_enabled) - conf.sedumi_enabled = pod_pkg_config('sedumi') && logical(exist('sedumi','file')); - end - - if (conf.sedumi_enabled) - % sedumiA=[10,2,3,4;5,7,6,4]; - % sedumib=[4;6]; - % sedumic=[0;1;0;1]; - % sedumiT=sedumi(sedumiA,sedumib,sedumic);%,struct('f',4),struct('fid',0)); - % if(~sedumiT) - % error('SeDuMi seems to have encountered a problem. Please verify that your SeDuMi install is working.'); - % end - elseif nargout<1 - disp(' '); - disp(' SeDuMi not found. SeDuMi support will be disabled.'); - disp(' To re-enable, add SeDuMi to your matlab path and rerun addpath_drake.'); - disp(' SeDuMi can be downloaded for free from http://sedumi.ie.lehigh.edu/ '); - disp(' '); - end - case 'mosek' conf.mosek_enabled = logical(exist('mosekopt','file')); if (~conf.mosek_enabled) @@ -294,17 +259,6 @@ disp(' '); end - case 'yalmip' - conf.yalmip_enabled = logical(exist('sdpvar','file')); - if (~conf.yalmip_enabled) - conf.yalmip_enabled = pod_pkg_config('yalmip') && logical(exist('sdpvar','file')); - end - if ~conf.yalmip_enabled && nargout<1 - disp(' '); - disp(' YALMIP not found. To enable, install YALMIP (e.g. by cloning https://github.com/RobotLocomotion/yalmip into drake-distro and running make).'); - disp(' '); - end - case 'rigidbodyconstraint_mex' conf.rigidbodyconstraint_mex_enabled = (exist('constructPtrRigidBodyConstraintmex','file')==3); if ~conf.rigidbodyconstraint_mex_enabled && nargout<1 @@ -321,54 +275,6 @@ disp(' '); end - case 'avl' - if ~isfield(conf,'avl') || isempty(conf.avl) - path_to_avl = getCMakeParam('AVL_EXECUTABLE'); - if isempty(path_to_avl) || strcmp(path_to_avl,'AVL_EXECUTABLE-NOTFOUND') - if nargout<1 - disp(' '); - disp(' AVL support is disabled. To enable it, install AVL from here: http://web.mit.edu/drela/Public/web/avl/, then add it to the matlab path or set the path to the avl executable explicitly using editDrakeConfig(''avl'',path_to_avl_executable) and rerun make'); - disp(' '); - end - conf.avl = ''; - else - conf.avl = path_to_avl; - end - end - conf.avl_enabled = ~isempty(conf.avl); - - case 'ffmpeg' - if ~isfield(conf,'ffmpeg') || isempty(conf.ffmpeg) - path_to_ffmpeg = getCMakeParam('FFMPEG_EXECUTABLE'); - if isempty(path_to_ffmpeg) || strcmp(path_to_ffmpeg,'FFMPEG_EXECUTABLE-NOTFOUND') - if nargout<1 - disp(' '); - disp(' FFmpeg support is disabled. To enable it, install FFmpeg or Libav, then re-run CMake.'); - disp(' '); - end - conf.ffmpeg = ''; - else - conf.ffmpeg = path_to_ffmpeg; - end - end - conf.ffmpeg_enabled = ~isempty(conf.ffmpeg); - - case 'xfoil' - if ~isfield(conf,'xfoil') || isempty(conf.xfoil) - path_to_xfoil = getCMakeParam('XFOIL_EXECUTABLE'); - if isempty(path_to_xfoil) || strcmp(path_to_xfoil,'XFOIL_EXECUTABLE-NOTFOUND') - if nargout<1 - disp(' '); - disp(' XFOIL support is disabled. To enable it, install XFOIL from here: http://web.mit.edu/drela/Public/web/xfoil/, then add it to the matlab path or set the path to the xfoil executable explicitly using editDrakeConfig(''xfoil'',path_to_avl_executable) and rerun addpath_drake'); - disp(' '); - end - conf.xfoil = ''; - else - conf.xfoil = path_to_xfoil; - end - end - conf.xfoil_enabled = ~isempty(conf.xfoil); - case 'fmincon' conf.fmincon_enabled = logical(exist('fmincon.m','file')); if(~conf.fmincon_enabled) @@ -409,14 +315,6 @@ end end - case 'iris' - conf.iris_enabled = logical(exist('+iris/inflate_region.m','file')); - if ~conf.iris_enabled && nargout<1 - disp(' '); - disp(' iris (Iterative Regional Inflation by SDP) is disabled. To enable it, install the IRIS matlab package from here: https://github.com/rdeits/iris-distro and re-run addpath_drake.'); - disp(' '); - end - case 'cpp_bindings' conf.cpp_bindings_enabled = logical(exist('+rbtree/RigidBodyTree.m','file')); if ~conf.cpp_bindings_enabled && nargout < 1 diff --git a/drake/matlab/util/debugMexEval.m b/drake/matlab/util/debugMexEval.m deleted file mode 100644 index 3f9724c86dbe..000000000000 --- a/drake/matlab/util/debugMexEval.m +++ /dev/null @@ -1,95 +0,0 @@ -function varargout = debugMexEval(fun,varargin) -% syntax is equavalent to feval, but this routine writes the inputs to a -% .mat file, which can be loaded and run from a standalone application to -% help debug mex files. -% -% to run it from the command line, run drake_debug_mex.sh (in the build/bin -% directory). -% - -% note: adding the -DMX_COMPAT_32 changed my symbol from _mxGetProperty_730 -% to _mxGetProperty_700, which is what I needed - -% note: debugMex executable keeps a global table of DrakeMexPointers and -% fills in the right pointer. will need to handle the case that this -% pointer does not exists, and give a useful warning so that people put a -% debugMexEval around the function that creates that pointer, as well. - -% note: it appears that the matrix library cannot load matlab class objects -% with the matlab engine disconnected. The work-around is that I write out the -% class objects passed in here as structures, and the debugMex executable -% overloads the mxGetProperty method using this technique: -% http://www.ibm.com/developerworks/library/l-glibc/index.html -% https://blogs.oracle.com/DatabaseEmporium/entry/where_is_ld_preload_under -% sigh. - -typecheck(fun,'char'); -if exist(fun)~=3, - error('the first argument should be a mex function'); -end - -% logic to keep track of individual function calls -persistent count; -if isempty(count), - count = 1; - appendstr = ''; -else - count = count+1; - appendstr = '-append'; -end -countstr = sprintf('%d',count); -if (length(countstr)>5) error('oops. need to increase the count limit'); end -countstr=[repmat('0',1,5-length(countstr)),countstr]; - -% convert classes to structures, so that they can be loaded without the -% matlab engine attached. (note: i don't feel like I should have to do -% this!) -% todo: need to do this recursively (e.g, for properties that are classes) -S = warning('off'); -for i=1:length(varargin) - varargin_to_write{i} = obj2struct(varargin{i}); -end -warning(S); - -% Write out consequitive calls with the notation nrhs_0001, etc. -eval(sprintf('fun_%s = which(fun);',countstr)); -eval(sprintf('nrhs_%s = length(varargin);',countstr)); -eval(sprintf('nlhs_%s = nargout;',countstr)); -eval(sprintf('varargin_%s = varargin_to_write;',countstr)); -eval(sprintf('save([''/tmp/mex_debug.mat''],''fun_%s'',''nrhs_%s'',''nlhs_%s'',''varargin_%s'',''%s'')',countstr,countstr,countstr,countstr,appendstr)); - -varargout=cell(1,nargout); -[varargout{:}] = feval(fun,varargin{:}); - - -end - - -function s = obj2struct(obj) - -if isobject(obj) - if numel(obj)>1 - for i=1:numel(obj) % support obj arrays - s(i) = struct(obj(i)); - end - else - s = struct(obj); % obj(i) doesn't work for everything (e.g. container.Map objects) - end - if isfield(s,'debug_mex_classname') - error('i assumed that you didn''t use this as a property name'); - end - [s.debug_mex_classname] = deal(class(obj)); -else - s = obj; -end - -if isstruct(s) - f = fieldnames(s); - for i=1:numel(s) - for j=1:numel(f) - s(i).(f{j})=obj2struct(s(i).(f{j})); - end - end -end - -end \ No newline at end of file diff --git a/drake/matlab/util/dev/debugMexTest.cpp b/drake/matlab/util/dev/debugMexTest.cpp deleted file mode 100644 index 2fe9b9a02943..000000000000 --- a/drake/matlab/util/dev/debugMexTest.cpp +++ /dev/null @@ -1,25 +0,0 @@ - -// prints the input - -#include - -#define UNUSED(x) (void)(x) - -DLL_EXPORT_SYM -void mexFunction(int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[]) { - UNUSED(nlhs); - UNUSED(plhs); - - if (nrhs > 0) { - double v = mxGetScalar(prhs[0]); - char buf[100]; - mxGetString(prhs[1], buf, 100); - - mxArray* C = mxGetProperty(prhs[2], 0, "C"); - if (!C) mexErrMsgIdAndTxt("debugMexTest", "failed to get property C"); - - double* pC = mxGetPrSafe(C); - - mexPrintf("%f,%s, C=[%f,%f]\n", v, buf, pC[0], pC[1]); - } -} diff --git a/drake/matlab/util/dev/debugMexTester.m b/drake/matlab/util/dev/debugMexTester.m deleted file mode 100644 index ef9defc6ed0c..000000000000 --- a/drake/matlab/util/dev/debugMexTester.m +++ /dev/null @@ -1,10 +0,0 @@ -function debugMexTester - -% run this method, then run build/bin/drake_debug_mex.sh at the -% linux command line - -doubleIntegrator = LinearSystem([0 1; 0 0],[0;1],[],[],[1 0],0); - -for i=1:10 - debugMexEval('debugMexTest',i,char('a'+i-1),doubleIntegrator); -end \ No newline at end of file diff --git a/drake/matlab/util/drakeDebugMex.cpp b/drake/matlab/util/drakeDebugMex.cpp deleted file mode 100644 index cde9c3bb6649..000000000000 --- a/drake/matlab/util/drakeDebugMex.cpp +++ /dev/null @@ -1,113 +0,0 @@ - -/* - * Read the documentation in debugMexEval.m for instructions. - * Happy bugfinding! - Russ - */ - -#include -#include -#include - -#include -#include -#include - -#include "drake/matlab/util/MexWrapper.h" - -#include -#include - -using namespace std; - -void cleanupDrakeMexPointers(void) { - // intentionally left blank; overloaded in debugMexLib.cpp using a - // DYLD_INSERT_LIBRARIES -} - -// todo: handle the variable arguments case -int mexPrintf(const char* message) { - return printf("%s", message); -} - -mxArray* mexCallMATLABWithTrap(int nlhs, mxArray* plhs[], int nrhs, - mxArray* prhs[], const char* functionName) { - printf("called mexCallMATLABWithTrap.\n"); - return NULL; -} - -// todo: implement stubs for other mex functions (mexErrMsgAndTxt, ...) here - -// todo: take the mex function and dynamically load / run it. -int main( - int argc, - char* argv[]) { - map mexfiles; - map::iterator iter; - - // load inputs from matfile - MATFile* pmatfile = matOpen("/tmp/mex_debug.mat", "r"); - if (!pmatfile) { - fprintf(stderr, "Failed to open %s\n", "/tmp/mex_debug.mat"); - exit(EXIT_FAILURE); - } - - int i, count = 1; - char buff[6], countstr[6] = "00000"; - string name; - - while (true) { - snprintf(buff, sizeof(buff), "%d", count); - memcpy(&countstr[5 - strlen(buff)], buff, strlen(buff)); - - name = "fun_"; - name += countstr; - mxArray* fun = matGetVariable(pmatfile, name.c_str()); - if (!fun) break; // then we've gotten to the end of the input "tape" - - char* str = mxArrayToString(fun); - string funstr(str); - mxFree(str); - - iter = mexfiles.find(funstr); - if (iter == mexfiles.end()) { - MexWrapper mex = MexWrapper(funstr); - pair::iterator, bool> ret; - ret = mexfiles.insert(pair(funstr, mex)); - iter = ret.first; - } - - name = "varargin_"; - name += countstr; - mxArray* varargin = matGetVariable(pmatfile, name.c_str()); - - name = "nrhs_"; - name += countstr; - int nrhs = mxGetScalar(matGetVariable(pmatfile, name.c_str())); - - name = "nlhs_"; - name += countstr; - int nlhs = mxGetScalar(matGetVariable(pmatfile, name.c_str())); - - mxArray** plhs = new mxArray* [nlhs]; - mxArray** prhs = new mxArray* [nrhs]; - for (i = 0; i < nrhs; i++) prhs[i] = mxGetCell(varargin, i); - - printf("%s: %s\n", countstr, funstr.c_str()); - - iter->second.mexFunction(nlhs, plhs, nrhs, - const_cast(prhs)); - - mxDestroyArray(varargin); - for (i = 0; i < nlhs; i++) mxDestroyArray(plhs[i]); - - delete[] plhs; - - count++; - } - - // cleanup - cleanupDrakeMexPointers(); - - matClose(pmatfile); - exit(EXIT_SUCCESS); -} diff --git a/drake/matlab/util/test/CMakeLists.txt b/drake/matlab/util/test/CMakeLists.txt index d9de7138dc18..a7b45018d937 100644 --- a/drake/matlab/util/test/CMakeLists.txt +++ b/drake/matlab/util/test/CMakeLists.txt @@ -1,8 +1,3 @@ -# tk 20141113 debugMexTest causes compilation errors on Ubuntu 32 bit -# See https://github.com/RobotLocomotion/drake/issues/553 -# debugMexTester.m and debugMexTest.cpp were moved to dev -# drake_add_mex(debugMexTest debugMexTest.cpp) - drake_add_matlab_test(NAME util/test/PassByValueMapTest COMMAND PassByValueMapTest) drake_add_matlab_test(NAME util/test/angleDiffTest COMMAND angleDiffTest) drake_add_matlab_test(NAME util/test/asintest REQUIRES spotless COMMAND asintest) @@ -46,4 +41,3 @@ drake_add_matlab_test(NAME util/test/testRotmat2rpy COMMAND testRotmat2rpy) drake_add_matlab_test(NAME util/test/testTransform COMMAND testTransform) drake_add_matlab_test(NAME util/test/test_datan2 COMMAND test_datan2) drake_add_matlab_test(NAME util/test/tvsumtest COMMAND tvsumtest) - diff --git a/externals/avl b/externals/avl deleted file mode 160000 index b67837fa737a..000000000000 --- a/externals/avl +++ /dev/null @@ -1 +0,0 @@ -Subproject commit b67837fa737afdf7a56655b044242619246b3ada diff --git a/externals/iris b/externals/iris deleted file mode 160000 index 49c347f46371..000000000000 --- a/externals/iris +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 49c347f46371327c0eda4c65eddcb5cd5815e350 diff --git a/externals/meshconverters b/externals/meshconverters deleted file mode 160000 index 07b848fa26fe..000000000000 --- a/externals/meshconverters +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 07b848fa26fe107c269439a7de14ef82429dda76 diff --git a/externals/sedumi b/externals/sedumi deleted file mode 160000 index c0aef9460846..000000000000 --- a/externals/sedumi +++ /dev/null @@ -1 +0,0 @@ -Subproject commit c0aef94608464247eb2ee8fe53b0681259228972 diff --git a/externals/signalscope b/externals/signalscope deleted file mode 160000 index f22243169381..000000000000 --- a/externals/signalscope +++ /dev/null @@ -1 +0,0 @@ -Subproject commit f22243169381f99f29e534931014557b50b4af95 diff --git a/externals/spotless b/externals/spotless deleted file mode 160000 index 5ab23370bf1a..000000000000 --- a/externals/spotless +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 5ab23370bf1a3b1f3bb176361d3612389be15276 diff --git a/externals/xfoil b/externals/xfoil deleted file mode 160000 index d11a1544b536..000000000000 --- a/externals/xfoil +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d11a1544b53623c01bb3b0cceb5862311be0e1f8 diff --git a/externals/yalmip b/externals/yalmip deleted file mode 160000 index 2a299b798e08..000000000000 --- a/externals/yalmip +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 2a299b798e08ddc9c343d044578b59ece5b036a0