diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 17215dee440d..7e1db134df80 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -949,7 +949,7 @@ drake_cc_optional_library( ":mathematical_program", ":mathematical_program_result", "//common:drake_export", - "@ipopt", + "@ipopt_internal//:ipopt", ], ) @@ -974,7 +974,7 @@ drake_cc_variant_library( ":ipopt_solver_internal", "//common:unused", "//math:autodiff", - "@ipopt", + "@ipopt_internal//:ipopt", ], ) @@ -1486,7 +1486,7 @@ drake_cc_googletest( ] + select({ "//conditions:default": [ ":ipopt_solver_internal", - "@ipopt", + "@ipopt_internal//:ipopt", ], "//tools:no_ipopt": [ ], @@ -1514,7 +1514,7 @@ drake_cc_googletest( "//common/test_utilities:expect_throws_message", ] + select({ "//conditions:default": [ - "@ipopt", + "@ipopt_internal//:ipopt", ], "//tools:no_ipopt": [ ], @@ -1532,7 +1532,9 @@ drake_sh_test( srcs = [":ipopt_solver_test"], args = select({ ":osx": [ - # SPRAL is a Linux-only feature, for now. + # SPRAL is the default on macOS, so ipopt_solver_test already has + # us covered. Only on Ubuntu (where MUMPS is the default) do we + # need to run-run this test. "--gtest_filter=-*", ], "//conditions:default": [ @@ -2069,6 +2071,7 @@ drake_cc_googletest( ":csdp_solver", ":gurobi_solver", ":ipopt_solver", + ":ipopt_solver_internal", ":linear_program_examples", ":mosek_solver", ":nlopt_solver", diff --git a/solvers/ipopt_solver.h b/solvers/ipopt_solver.h index 7f3fe62eb701..354db084fbe1 100644 --- a/solvers/ipopt_solver.h +++ b/solvers/ipopt_solver.h @@ -46,7 +46,7 @@ struct IpoptSolverDetails { * using Drake's MathematicalProgram. * * The IpoptSolver is NOT threadsafe to call in parallel. This is due to Ipopt's - * reliance on the MUMPs linear solver which is not safe to call concurrently + * reliance on the MUMPS linear solver which is not safe to call concurrently * (see https://github.com/coin-or/Ipopt/issues/733). This can be resolved by * enabling the SPRAL solver (see Drake issue * https://github.com/RobotLocomotion/drake/issues/21476). diff --git a/solvers/solve.cc b/solvers/solve.cc index 27591fd456d8..7c5d5ea5fafc 100644 --- a/solvers/solve.cc +++ b/solvers/solve.cc @@ -93,9 +93,9 @@ std::vector SolveInParallel( ? *((*solver_ids)[i]) : ChooseBestSolver(*progs[i]); - // IPOPT's MUMPs linear solver is not thread-safe. Therefore, if we are + // IPOPT's MUMPS linear solver is not thread-safe. Therefore, if we are // operating in parallel we need to skip this program. - // TODO(#21476) Revisit this logic after we have SPRAL available. + // TODO(#21476) Only force serial mode when MUMPS is used (not for SPRAL). if (in_parallel && solver_id == IpoptSolver::id()) { static const logging::Warn log_once( "IpoptSolver cannot currently solve programs in parallel, so will be " diff --git a/solvers/test/ipopt_solver_internal_test.cc b/solvers/test/ipopt_solver_internal_test.cc index 5459b21a4088..52b5adf1d589 100644 --- a/solvers/test/ipopt_solver_internal_test.cc +++ b/solvers/test/ipopt_solver_internal_test.cc @@ -282,8 +282,9 @@ GTEST_TEST(TestIpoptSolver, SupportedLinearSolvers) { const std::vector actual = GetSupportedIpoptLinearSolvers(); std::vector expected; if (kApple) { - // Homebrew doesn't provide SPRAL. - expected.emplace_back("mumps"); + // Homebrew doesn't provide a usable MUMPS library for us to build against, + // so SPRAL is the only available option. + expected.emplace_back("spral"); } else { expected.emplace_back("mumps"); expected.emplace_back("spral"); diff --git a/solvers/test/solve_in_parallel_test.cc b/solvers/test/solve_in_parallel_test.cc index c753b629a60e..6816b34e14bd 100644 --- a/solvers/test/solve_in_parallel_test.cc +++ b/solvers/test/solve_in_parallel_test.cc @@ -6,6 +6,7 @@ #include "drake/solvers/csdp_solver.h" #include "drake/solvers/gurobi_solver.h" #include "drake/solvers/ipopt_solver.h" +#include "drake/solvers/ipopt_solver_internal.h" #include "drake/solvers/mosek_solver.h" #include "drake/solvers/nlopt_solver.h" #include "drake/solvers/osqp_solver.h" @@ -304,9 +305,15 @@ TEST_P(SolveInParallelIntegrationTest, Gurobi) { TEST_P(SolveInParallelIntegrationTest, Ipopt) { QuadraticProgram1 qp{CostForm::kNonSymbolic, ConstraintForm::kNonSymbolic}; - // This linear solver is known to not be threadsafe. We want to be sure that - // this does not cause SolveInParallel to crash. - qp.prog()->SetSolverOption(IpoptSolver::id(), "linear_solver", "mumps"); + // The MUMPS linear solver is known to not be threadsafe. We want to be sure + // that this does not cause SolveInParallel to crash. However, some platforms + // don't have MUMPS available, so we need to check before setting it. + for (const auto& linear_solver : internal::GetSupportedIpoptLinearSolvers()) { + if (linear_solver == "mumps") { + qp.prog()->SetSolverOption(IpoptSolver::id(), "linear_solver", "mumps"); + break; + } + } for (const auto& result : Run(IpoptSolver::id(), *qp.prog())) { qp.CheckSolution(result); } diff --git a/tools/install/libdrake/BUILD.bazel b/tools/install/libdrake/BUILD.bazel index 3c594c8c34ef..8a92c51cca5e 100644 --- a/tools/install/libdrake/BUILD.bazel +++ b/tools/install/libdrake/BUILD.bazel @@ -149,26 +149,6 @@ install( ], ) -# Depend on IPOPT's shared library iff IPOPT is enabled and we're on a platform -# that uses the host OS shared library. -selects.config_setting_group( - name = "ipopt_not_shared", - match_any = [ - "//tools:no_ipopt", - "//tools/cc_toolchain:linux", - ], -) - -cc_library( - name = "ipopt_deps", - deps = selects.with_or({ - "//conditions:default": [ - "@ipopt", - ], - ":ipopt_not_shared": [], - }), -) - # Depend on Gurobi's shared library iff Gurobi is enabled. cc_library( name = "gurobi_deps", @@ -238,7 +218,6 @@ cc_library( name = "libdrake_runtime_so_deps", deps = [ ":gurobi_deps", - ":ipopt_deps", ":mosek_deps", ":usd_deps", ":x11_deps", diff --git a/tools/wheel/image/dependencies/patches/mumps/patch.cmake b/tools/wheel/image/dependencies/patches/mumps/patch.cmake deleted file mode 100644 index 49bfe0857c19..000000000000 --- a/tools/wheel/image/dependencies/patches/mumps/patch.cmake +++ /dev/null @@ -1,4 +0,0 @@ -execute_process( - COMMAND git apply ${mumps_patch}/patch.diff - WORKING_DIRECTORY ${mumps_source} - ) diff --git a/tools/wheel/image/dependencies/patches/mumps/patch.diff b/tools/wheel/image/dependencies/patches/mumps/patch.diff deleted file mode 100644 index e6257b30e535..000000000000 --- a/tools/wheel/image/dependencies/patches/mumps/patch.diff +++ /dev/null @@ -1,73 +0,0 @@ -The Makefile.macos.SEQ patch is largely adapted from Homebrew: -https://github.com/Homebrew/homebrew-core/blob/c6d166f556351ecfade14930021e2217b59279ec/Formula/ipopt.rb#L31 - -diff --git a/Make.inc/Makefile.inc.generic.SEQ b/Make.inc/Makefile.macos.SEQ -similarity index 96% -copy from Make.inc/Makefile.inc.generic.SEQ -copy to Make.inc/Makefile.macos.SEQ -index 2558f30..dac9334 100644 ---- a/Make.inc/Makefile.inc.generic.SEQ -+++ b/Make.inc/Makefile.macos.SEQ -@@ -94,7 +94,7 @@ IORDERINGSC = $(IMETIS) $(IPORD) $(ISCOTCH) - PLAT = - # Library extension, + C and Fortran "-o" option - # may be different under Windows --LIBEXT = .a -+LIBEXT = .dylib - OUTC = -o - OUTF = -o - # RM : remove files -@@ -102,16 +102,15 @@ RM = /bin/rm -f - # CC : C compiler - CC = cc - # FC : Fortran 90 compiler --FC = f90 -+FC = gfortran - # FL : Fortran linker --FL = f90 -+FL = $(FC) - # AR : Archive object in a library - # keep a space at the end if options have to be separated from lib name --AR = ar vr -+AR = $(FC) -dynamiclib -undefined dynamic_lookup -Wl,-install_name,@rpath/$(notdir $@) -o - # RANLIB : generate index of an archive file - # (optionnal use "RANLIB = echo" in case of problem) --RANLIB = ranlib --#RANLIB = echo -+RANLIB = echo - - # DEFINE HERE YOUR LAPACK LIBRARY - -@@ -143,8 +142,8 @@ LIBOTHERS = -lpthread - CDEFS = -DAdd_ - - #COMPILER OPTIONS --OPTF = -O --OPTC = -O -I. -+OPTF = -fPIC -O -fallow-argument-mismatch -+OPTC = -fPIC -O -I. - OPTL = -O - - #Sequential: -diff --git a/Makefile b/Makefile -index 3c0f645..55ac6ba 100644 ---- a/Makefile -+++ b/Makefile -@@ -59,6 +59,17 @@ $(libdir)/libpord$(PLAT)$(LIBEXT): - cp $(LPORDDIR)/libpord$(LIBEXT) $@; \ - fi; - -+install: d -+ if ( test ! -d $(PREFIX)/lib ) ; then mkdir -p $(PREFIX)/lib ; fi -+ if ( test ! -d $(PREFIX)/include ) ; then mkdir -p $(PREFIX)/include ; fi -+ if ( test ! -d $(PREFIX)/include/mumps_seq ) ; then mkdir -p $(PREFIX)/include/mumps_seq ; fi -+ for lib in libseq/*$(LIBEXT) $(libdir)/*$(LIBEXT) ; do \ -+ ginstall -t $(PREFIX)/lib $$lib; \ -+ install_name_tool -id $(PREFIX)/lib/$$(basename $$lib) $(PREFIX)/lib/$$(basename $$lib); \ -+ done -+ ginstall -m 644 -t $(PREFIX)/include include/*.h -+ ginstall -m 644 -t $(PREFIX)/include/mumps_seq libseq/mpi.h -+ - clean: - (cd src; $(MAKE) clean) - (cd examples; $(MAKE) clean) diff --git a/tools/wheel/image/dependencies/projects.cmake b/tools/wheel/image/dependencies/projects.cmake index c9f49ee74e55..da284f7d90d8 100644 --- a/tools/wheel/image/dependencies/projects.cmake +++ b/tools/wheel/image/dependencies/projects.cmake @@ -27,23 +27,3 @@ if(NOT APPLE) set(lapack_md5 "d70fc27a8bdebe00481c97c728184f09") list(APPEND ALL_PROJECTS lapack) endif() - -# ipopt (requires mumps) -if(APPLE_ARM64) - set(mumps_version 5.4.1) # Latest available in Ubuntu. - set(mumps_url - "http://archive.ubuntu.com/ubuntu/pool/universe/m/mumps/mumps_${mumps_version}.orig.tar.gz" - "http://mumps.enseeiht.fr/MUMPS_${mumps_version}.tar.gz" - ) - set(mumps_md5 "93be789bf9c6c341a78c16038da3241b") - set(mumps_dlname "mumps-${mumps_version}.tar.gz") - list(APPEND ALL_PROJECTS mumps) - - # This must match the version in tools/workspace/ipopt_internal_fromsource. - # The matching is automatically enforced by a linter script. - set(ipopt_version 3.14.16) - set(ipopt_url "https://github.com/coin-or/Ipopt/archive/refs/tags/releases/${ipopt_version}.tar.gz") - set(ipopt_md5 "f94822be08b1f6e109261f305799b0ae") - set(ipopt_dlname "ipopt-${ipopt_version}.tar.gz") - list(APPEND ALL_PROJECTS ipopt) -endif() diff --git a/tools/wheel/image/dependencies/projects/ipopt.cmake b/tools/wheel/image/dependencies/projects/ipopt.cmake deleted file mode 100644 index a46e7ece9973..000000000000 --- a/tools/wheel/image/dependencies/projects/ipopt.cmake +++ /dev/null @@ -1,29 +0,0 @@ -if(NOT APPLE) - message(FATAL_ERROR "mumps should only be built on macOS") -endif() - -ExternalProject_Add(ipopt - URL ${ipopt_url} - URL_MD5 ${ipopt_md5} - DOWNLOAD_NAME ${ipopt_dlname} - DEPENDS mumps - ${COMMON_EP_ARGS} - BUILD_IN_SOURCE 1 - CONFIGURE_COMMAND ./configure - --prefix=${CMAKE_INSTALL_PREFIX} - --disable-shared - FFLAGS=-fPIC - CFLAGS=-fPIC - CXXFLAGS=-fPIC - LDFLAGS=-L${CMAKE_INSTALL_PREFIX}/lib - --with-lapack-lflags=-framework\ Accelerate - --with-mumps-lflags=-ldmumps\ -lmpiseq\ -lmumps_common\ -lpord - --with-mumps-cflags=-I${CMAKE_INSTALL_PREFIX}/include - CPPFLAGS=-I${CMAKE_INSTALL_PREFIX}/include/mumps_seq - BUILD_COMMAND make - INSTALL_COMMAND make install - ) - -extract_license(ipopt - LICENSE -) diff --git a/tools/wheel/image/dependencies/projects/mumps.cmake b/tools/wheel/image/dependencies/projects/mumps.cmake deleted file mode 100644 index 8be5e50664a7..000000000000 --- a/tools/wheel/image/dependencies/projects/mumps.cmake +++ /dev/null @@ -1,24 +0,0 @@ -if(NOT APPLE) - message(FATAL_ERROR "mumps should only be built on macOS") -endif() - -ExternalProject_Add(mumps - URL ${mumps_url} - URL_MD5 ${mumps_md5} - DOWNLOAD_NAME ${mumps_dlname} - ${COMMON_EP_ARGS} - BUILD_IN_SOURCE 1 - PATCH_COMMAND ${CMAKE_COMMAND} - -Dmumps_patch=${CMAKE_SOURCE_DIR}/patches/mumps - -Dmumps_source=${CMAKE_BINARY_DIR}/src/mumps - -P ${CMAKE_SOURCE_DIR}/patches/mumps/patch.cmake - CONFIGURE_COMMAND ${CMAKE_COMMAND} -E copy - ${CMAKE_BINARY_DIR}/src/mumps/Make.inc/Makefile.macos.SEQ - ${CMAKE_BINARY_DIR}/src/mumps/Makefile.inc - BUILD_COMMAND make d - INSTALL_COMMAND make PREFIX=${CMAKE_INSTALL_PREFIX} install - ) - -extract_license(mumps - LICENSE -) diff --git a/tools/workspace/BUILD.bazel b/tools/workspace/BUILD.bazel index 684cc17d1328..317a939e1e49 100644 --- a/tools/workspace/BUILD.bazel +++ b/tools/workspace/BUILD.bazel @@ -50,7 +50,7 @@ drake_py_binary( "@fcl_internal//:__subpackages__", "@gz_math_internal//:__subpackages__", "@gz_utils_internal//:__subpackages__", - "@ipopt_internal_fromsource//:__subpackages__", + "@ipopt_internal//:__subpackages__", "@msgpack_internal//:__subpackages__", "@nlopt_internal//:__subpackages__", "@qhull_internal//:__subpackages__", @@ -115,7 +115,7 @@ _DRAKE_EXTERNAL_PACKAGE_INSTALLS = ["@%s//:install" % p for p in [ "gklib_internal", "gz_math_internal", "gz_utils_internal", - "ipopt", + "ipopt_internal", "lcm", "libpng_internal", "libtiff_internal", diff --git a/tools/workspace/clp_internal/package.BUILD.bazel b/tools/workspace/clp_internal/package.BUILD.bazel index ad27aaf26ca2..d898f19f2886 100644 --- a/tools/workspace/clp_internal/package.BUILD.bazel +++ b/tools/workspace/clp_internal/package.BUILD.bazel @@ -47,8 +47,6 @@ _SRCS = glob( # We treat COIN_HAS_AMD, COIN_HAS_CHOLMOD, and COIN_HAS_GLPK as OFF. "**/ClpCholeskyUfl*", # We treat COIN_HAS_MUMPS as OFF. - # TODO(jwnimmer-tri) We can probably enable this. I've left it off for - # now only out of inertia -- Ubuntu builds CLP without MUMPS. "**/ClpCholeskyMumps*", # We treat COIN_HAS_WSMP as OFF. "**/ClpCholeskyWssmp*", @@ -95,15 +93,13 @@ _AUTOCONF_UNDEFINES = [ "HAVE_DLFCN_H", "HAVE_IEEEFP_H", "HAVE_MEMORY_H", - # TODO(jwnimmer-tri) We can probably enable this. I've left it off for now - # only out of inertia -- Ubuntu builds CLP without MUMPS. - "COIN_HAS_MUMPS", # Optional dependencies that we don't use. "CLP_HAS_ABC", "COIN_HAS_AMD", "COIN_HAS_ASL", "COIN_HAS_CHOLMOD", "COIN_HAS_GLPK", + "COIN_HAS_MUMPS", "COIN_HAS_NETLIB", "COIN_HAS_OSI", "COIN_HAS_OSITESTS", diff --git a/tools/workspace/default.bzl b/tools/workspace/default.bzl index 4ce1df39d21b..9494a9d9e065 100644 --- a/tools/workspace/default.bzl +++ b/tools/workspace/default.bzl @@ -38,8 +38,7 @@ load("//tools/workspace/gz_math_internal:repository.bzl", "gz_math_internal_repo load("//tools/workspace/gz_utils_internal:repository.bzl", "gz_utils_internal_repository") # noqa load("//tools/workspace/highway_internal:repository.bzl", "highway_internal_repository") # noqa load("//tools/workspace/ipopt:repository.bzl", "ipopt_repository") -load("//tools/workspace/ipopt_internal_fromsource:repository.bzl", "ipopt_internal_fromsource_repository") # noqa -load("//tools/workspace/ipopt_internal_pkgconfig:repository.bzl", "ipopt_internal_pkgconfig_repository") # noqa +load("//tools/workspace/ipopt_internal:repository.bzl", "ipopt_internal_repository") # noqa load("//tools/workspace/lapack:repository.bzl", "lapack_repository") load("//tools/workspace/lcm:repository.bzl", "lcm_repository") load("//tools/workspace/libblas:repository.bzl", "libblas_repository") @@ -226,10 +225,8 @@ def add_default_repositories( highway_internal_repository(name = "highway_internal", mirrors = mirrors) # noqa if "ipopt" not in excludes: ipopt_repository(name = "ipopt") - if "ipopt_internal_fromsource" not in excludes: - ipopt_internal_fromsource_repository(name = "ipopt_internal_fromsource", mirrors = mirrors) # noqa - if "ipopt_internal_pkgconfig" not in excludes: - ipopt_internal_pkgconfig_repository(name = "ipopt_internal_pkgconfig") + if "ipopt_internal" not in excludes: + ipopt_internal_repository(name = "ipopt_internal", mirrors = mirrors) # noqa if "lapack" not in excludes: lapack_repository(name = "lapack") if "lcm" not in excludes: diff --git a/tools/workspace/ipopt/package.BUILD.bazel b/tools/workspace/ipopt/package.BUILD.bazel new file mode 100644 index 000000000000..59460e333b41 --- /dev/null +++ b/tools/workspace/ipopt/package.BUILD.bazel @@ -0,0 +1,13 @@ +# -*- bazel -*- + +load("@drake//tools/skylark:cc.bzl", "cc_library") + +package(default_visibility = ["//visibility:public"]) + +_MESSAGE = "DRAKE DEPRECATED: The @ipopt repository alias is no longer available, and there is no replacement. If you still something related to IPOPT, you may wish to copy the repository rule from a prior Drake release into your project. The deprecated code will be removed from Drake on or after 2025-04-01." # noqa + +cc_library( + name = "ipopt", + deps = ["@ipopt_internal//:ipopt"], + deprecation = _MESSAGE, +) diff --git a/tools/workspace/ipopt/repository.bzl b/tools/workspace/ipopt/repository.bzl index cbd37f388038..6fac6d08ac3c 100644 --- a/tools/workspace/ipopt/repository.bzl +++ b/tools/workspace/ipopt/repository.bzl @@ -1,17 +1,10 @@ -load("//tools/workspace:os.bzl", "os_specific_alias_repository") - -# How we build IPOPT depends on which platform we're on. -def ipopt_repository(name): - os_specific_alias_repository( - name = name, - mapping = { - "linux": [ - "ipopt=@ipopt_internal_fromsource//:ipopt", - "install=@ipopt_internal_fromsource//:install", - ], - "osx": [ - "ipopt=@ipopt_internal_pkgconfig//:ipopt_internal_pkgconfig", - "install=@ipopt_internal_pkgconfig//:install", - ], - }, +def _impl(repo_ctx): + repo_ctx.symlink( + Label("@drake//tools/workspace/ipopt:package.BUILD.bazel"), + "BUILD.bazel", ) + +ipopt_repository = repository_rule( + local = True, + implementation = _impl, +) diff --git a/tools/workspace/ipopt_internal_fromsource/BUILD.bazel b/tools/workspace/ipopt_internal/BUILD.bazel similarity index 79% rename from tools/workspace/ipopt_internal_fromsource/BUILD.bazel rename to tools/workspace/ipopt_internal/BUILD.bazel index 9925484670d6..5227a7a6124f 100644 --- a/tools/workspace/ipopt_internal_fromsource/BUILD.bazel +++ b/tools/workspace/ipopt_internal/BUILD.bazel @@ -19,9 +19,7 @@ drake_py_unittest( name = "lint_test", data = [ ":package.BUILD.bazel", - "//tools/wheel:image/dependencies/projects.cmake", - "@ipopt_internal_fromsource//:drake_repository_metadata.json", - "@ipopt_internal_fromsource//:src/Makefile.am", + "@ipopt_internal//:src/Makefile.am", ], tags = ["lint"], deps = [ diff --git a/tools/workspace/ipopt_internal_fromsource/package.BUILD.bazel b/tools/workspace/ipopt_internal/package.BUILD.bazel similarity index 97% rename from tools/workspace/ipopt_internal_fromsource/package.BUILD.bazel rename to tools/workspace/ipopt_internal/package.BUILD.bazel index 7c965b79bdba..cb6978d36295 100644 --- a/tools/workspace/ipopt_internal_fromsource/package.BUILD.bazel +++ b/tools/workspace/ipopt_internal/package.BUILD.bazel @@ -6,6 +6,7 @@ load( "@drake//tools/workspace/coinutils_internal:defs.bzl", "coin_cc_library", ) +load("@mumps_internal//:defs.bzl", MUMPS_ENABLED = "ENABLED") licenses(["reciprocal"]) # EPL-2.0 @@ -213,8 +214,9 @@ _SRCS_INITIAL = [ ] # In addition to _SRCS_INITIAL, we also add extra sources for certain solvers. -_SRCS_SOLVER_MUMPS_SPRAL = [ +_SRCS_SOLVER_MUMPS_SPRAL = ([ "src/Algorithm/LinearSolvers/IpMumpsSolverInterface.cpp", +] if MUMPS_ENABLED else []) + [ "src/Algorithm/LinearSolvers/IpSpralSolverInterface.cpp", ] @@ -275,7 +277,6 @@ _AUTOCONF_DEFINES = [ "STDC_HEADERS=1", # Optional dependencies that we do actually want to use. "IPOPT_HAS_LAPACK=1", - "IPOPT_HAS_MUMPS=1", "IPOPT_HAS_SPRAL=1", # No debug self-checks (the default). "IPOPT_CHECKLEVEL=0", @@ -286,7 +287,7 @@ _AUTOCONF_DEFINES = [ "IPOPTLIB_EXPORT=__attribute__ ((visibility (\"hidden\")))", "SIPOPTAMPLINTERFACELIB_EXPORT=", "SIPOPTLIB_EXPORT=", -] +] + (["IPOPT_HAS_MUMPS=1"] if MUMPS_ENABLED else []) _AUTOCONF_UNDEFINES = [ # Don't use these features of the standard library and/or host system. @@ -337,7 +338,7 @@ _AUTOCONF_UNDEFINES = [ # This is actually used by the C++ code, but autoconf_configure_file can't # handle it. We'll use _CONFIG_PRIVATE_DEFINES for this instead, below. "IPOPT_LAPACK_FUNC", -] +] + ([] if MUMPS_ENABLED else ["IPOPT_HAS_MUMPS"]) _CONFIG_PRIVATE_DEFINES = [ "IPOPT_LAPACK_FUNC(name,NAME)=name##_", @@ -361,9 +362,10 @@ coin_cc_library( deps = [ "@blas", "@lapack", - "@mumps_internal//:dmumps_seq", "@spral_internal//:spral", - ], + ] + ([ + "@mumps_internal//:dmumps_seq", + ] if MUMPS_ENABLED else []), visibility = ["//visibility:public"], ) @@ -373,10 +375,10 @@ install( "LICENSE", # We must redistribute our code changes, per Ipopt's EPL-2.0 license. ":drake_ipopt.patch", - "@drake//tools/workspace/ipopt_internal_fromsource:patches", + "@drake//tools/workspace/ipopt_internal:patches", ], allowed_externals = [ - "@drake//tools/workspace/ipopt_internal_fromsource:patches", + "@drake//tools/workspace/ipopt_internal:patches", ], visibility = ["//visibility:public"], ) diff --git a/tools/workspace/ipopt_internal_fromsource/repository.bzl b/tools/workspace/ipopt_internal/repository.bzl similarity index 92% rename from tools/workspace/ipopt_internal_fromsource/repository.bzl rename to tools/workspace/ipopt_internal/repository.bzl index 4b4e4ab42307..f705dd648134 100644 --- a/tools/workspace/ipopt_internal_fromsource/repository.bzl +++ b/tools/workspace/ipopt_internal/repository.bzl @@ -1,6 +1,6 @@ load("//tools/workspace:github.bzl", "github_archive") -def ipopt_internal_fromsource_repository( +def ipopt_internal_repository( name, mirrors = None): github_archive( diff --git a/tools/workspace/ipopt_internal_fromsource/test/lint_test.py b/tools/workspace/ipopt_internal/test/lint_test.py similarity index 75% rename from tools/workspace/ipopt_internal_fromsource/test/lint_test.py rename to tools/workspace/ipopt_internal/test/lint_test.py index 51fa3f45708f..9ad0ba7e8beb 100644 --- a/tools/workspace/ipopt_internal_fromsource/test/lint_test.py +++ b/tools/workspace/ipopt_internal/test/lint_test.py @@ -24,8 +24,7 @@ def _parse_build(self, varname): """ result = [] contents = self._read( - "drake/tools/workspace/ipopt_internal_fromsource/" - + "package.BUILD.bazel") + "drake/tools/workspace/ipopt_internal/package.BUILD.bazel") lines = contents.splitlines() start_line = f"{varname} = [" end_line = "]" @@ -57,7 +56,7 @@ def _parse_make(self, varname, *, guard_line=None): path/to/file2 """ result = [] - contents = self._read("ipopt_internal_fromsource/src/Makefile.am") + contents = self._read("ipopt_internal/src/Makefile.am") lines = contents.splitlines() if guard_line is None: start_line = f"{varname} = \\" @@ -99,26 +98,3 @@ def test_srcs_solver_int32(self): self.assertSetEqual(self._parse_build("_SRCS_SOLVER_INT32"), self._parse_make("libipopt_la_SOURCES", guard_line="if !IPOPT_INT64")) - - def test_wheel_verison_pin(self): - """Checks that the repository rule and wheel agree on which version of - IPOPT we should be using. - """ - # Parse the Bazel version. - commit = json.loads(self._read( - "ipopt_internal_fromsource/" - "drake_repository_metadata.json"))["commit"] - prefix = "releases/" - self.assertTrue(commit.startswith(prefix), commit) - bazel_version = commit[len(prefix):] - - # Parse the Wheel version from the line `set(ipopt_version #.#.#)`. - projects = self._read( - "drake/tools/wheel/image/dependencies/projects.cmake") - prefix = "set(ipopt_version " - start = projects.index(prefix) + len(prefix) - end = projects.index(")", start) - wheel_version = projects[start:end] - - # Exact string match. - self.assertEqual(wheel_version, bazel_version) diff --git a/tools/workspace/ipopt_internal_pkgconfig/BUILD.bazel b/tools/workspace/ipopt_internal_pkgconfig/BUILD.bazel deleted file mode 100644 index 67914ea7e0a0..000000000000 --- a/tools/workspace/ipopt_internal_pkgconfig/BUILD.bazel +++ /dev/null @@ -1,3 +0,0 @@ -load("//tools/lint:lint.bzl", "add_lint_tests") - -add_lint_tests() diff --git a/tools/workspace/ipopt_internal_pkgconfig/repository.bzl b/tools/workspace/ipopt_internal_pkgconfig/repository.bzl deleted file mode 100644 index 45a7f37e00d9..000000000000 --- a/tools/workspace/ipopt_internal_pkgconfig/repository.bzl +++ /dev/null @@ -1,13 +0,0 @@ -load("//tools/workspace:pkg_config.bzl", "pkg_config_repository") - -def ipopt_internal_pkgconfig_repository(name): - pkg_config_repository( - name = name, - licenses = ["reciprocal"], # CPL-1.0 - modname = "ipopt", - # When using ipopt from pkg-config, there is nothing to install. - build_epilog = """ -load("@drake//tools/install:install.bzl", "install") -install(name = "install") -""", - ) diff --git a/tools/workspace/mumps_internal/package.BUILD.bazel b/tools/workspace/mumps_internal/package-enabled.BUILD.bazel similarity index 100% rename from tools/workspace/mumps_internal/package.BUILD.bazel rename to tools/workspace/mumps_internal/package-enabled.BUILD.bazel diff --git a/tools/workspace/mumps_internal/package-error.BUILD.bazel b/tools/workspace/mumps_internal/package-error.BUILD.bazel new file mode 100644 index 000000000000..5febc215976c --- /dev/null +++ b/tools/workspace/mumps_internal/package-error.BUILD.bazel @@ -0,0 +1,23 @@ +# -*- bazel -*- + +# This stub BUILD file for MUMPS contains the same public targets as the real +# BUILD file, always reports an error (from error.txt) during compilation, but +# does not report any loading-phase errors. This is useful to defer error +# reporting until after the loading phase, so that `bazel query` commands will +# still work even with MUMPS missing. + +load("@drake//tools/skylark:cc.bzl", "cc_library") + +genrule( + name = "error-message", + srcs = ["error.txt"], + outs = ["error-message.h"], + cmd = "cat $< 1>&2 && false", + visibility = ["//visibility:private"], +) + +cc_library( + name = "dmumps_seq", + hdrs = [":error-message.h"], + visibility = ["//visibility:public"], +) diff --git a/tools/workspace/mumps_internal/repository.bzl b/tools/workspace/mumps_internal/repository.bzl index 27a4b6ee1a7b..862a882889b5 100644 --- a/tools/workspace/mumps_internal/repository.bzl +++ b/tools/workspace/mumps_internal/repository.bzl @@ -1,4 +1,12 @@ def _impl(repo_ctx): + # We are enabled only on linux, not macOS. + enabled = repo_ctx.os.name == "linux" + repo_ctx.file("defs.bzl", content = "ENABLED = {}\n".format(enabled)) + if not enabled: + repo_ctx.file("error.txt", content = """ +ERROR: The mumps_internal repository rule is disabled on this operating system. +""") + # Symlink the relevant headers. hdrs = [ "dmumps_c.h", @@ -14,13 +22,17 @@ def _impl(repo_ctx): # Add the BUILD file. repo_ctx.symlink( - Label("@drake//tools/workspace/mumps_internal:package.BUILD.bazel"), + Label("{}:package-{}.BUILD.bazel".format( + "@drake//tools/workspace/mumps_internal", + "enabled" if enabled else "error", + )), "BUILD.bazel", ) mumps_internal_repository = repository_rule( doc = """Adds a repository rule for the host mumps library from Ubuntu. - This repository is not used on macOS. + This repository is not useful on macOS; the repository rule will evaluate + without error, but the cc_library would error if used in a build. """, local = True, implementation = _impl,