Skip to content

Commit

Permalink
[workspace] Build IPOPT from source on macOS
Browse files Browse the repository at this point in the history
One consequence is that MUMPS is no longer available as one of IPOPT's
linear solvers on macOS (because homebrew refuses to accept our pull
requests to package MUMPS standalone, after 9 months of us trying).
The only linear solver is SPRAL.

Remove now-irrelevant ipopt_internal_pkgconfig and therefore rename
ipopt_internal_fromsource to just plain ipopt_internal.

Remove now-irrelevant IPOPT code from the wheel build.

Relatedly, remove TODOs in CLP considering adding support for MUMPS,
both because we can't use it on macOS and also because we've recently
learned that MUMPS has global variables (is not threadsafe).

Deprecate the `@ipopt` repository alias.
  • Loading branch information
jwnimmer-tri committed Dec 18, 2024
1 parent f1f0cc3 commit 9be0c39
Show file tree
Hide file tree
Showing 25 changed files with 103 additions and 269 deletions.
13 changes: 8 additions & 5 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -949,7 +949,7 @@ drake_cc_optional_library(
":mathematical_program",
":mathematical_program_result",
"//common:drake_export",
"@ipopt",
"@ipopt_internal//:ipopt",
],
)

Expand All @@ -974,7 +974,7 @@ drake_cc_variant_library(
":ipopt_solver_internal",
"//common:unused",
"//math:autodiff",
"@ipopt",
"@ipopt_internal//:ipopt",
],
)

Expand Down Expand Up @@ -1486,7 +1486,7 @@ drake_cc_googletest(
] + select({
"//conditions:default": [
":ipopt_solver_internal",
"@ipopt",
"@ipopt_internal//:ipopt",
],
"//tools:no_ipopt": [
],
Expand Down Expand Up @@ -1514,7 +1514,7 @@ drake_cc_googletest(
"//common/test_utilities:expect_throws_message",
] + select({
"//conditions:default": [
"@ipopt",
"@ipopt_internal//:ipopt",
],
"//tools:no_ipopt": [
],
Expand All @@ -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": [
Expand Down Expand Up @@ -2069,6 +2071,7 @@ drake_cc_googletest(
":csdp_solver",
":gurobi_solver",
":ipopt_solver",
":ipopt_solver_internal",
":linear_program_examples",
":mosek_solver",
":nlopt_solver",
Expand Down
2 changes: 1 addition & 1 deletion solvers/ipopt_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -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).
Expand Down
4 changes: 2 additions & 2 deletions solvers/solve.cc
Original file line number Diff line number Diff line change
Expand Up @@ -93,9 +93,9 @@ std::vector<MathematicalProgramResult> 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 "
Expand Down
5 changes: 3 additions & 2 deletions solvers/test/ipopt_solver_internal_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -282,8 +282,9 @@ GTEST_TEST(TestIpoptSolver, SupportedLinearSolvers) {
const std::vector<std::string_view> actual = GetSupportedIpoptLinearSolvers();
std::vector<std::string_view> 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");
Expand Down
13 changes: 10 additions & 3 deletions solvers/test/solve_in_parallel_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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);
}
Expand Down
21 changes: 0 additions & 21 deletions tools/install/libdrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -154,26 +154,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",
Expand Down Expand Up @@ -243,7 +223,6 @@ cc_library(
name = "libdrake_runtime_so_deps",
deps = [
":gurobi_deps",
":ipopt_deps",
":mosek_deps",
":usd_deps",
":x11_deps",
Expand Down
4 changes: 0 additions & 4 deletions tools/wheel/image/dependencies/patches/mumps/patch.cmake

This file was deleted.

73 changes: 0 additions & 73 deletions tools/wheel/image/dependencies/patches/mumps/patch.diff

This file was deleted.

20 changes: 0 additions & 20 deletions tools/wheel/image/dependencies/projects.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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()
29 changes: 0 additions & 29 deletions tools/wheel/image/dependencies/projects/ipopt.cmake

This file was deleted.

24 changes: 0 additions & 24 deletions tools/wheel/image/dependencies/projects/mumps.cmake

This file was deleted.

4 changes: 2 additions & 2 deletions tools/workspace/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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__",
Expand Down Expand Up @@ -116,7 +116,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",
Expand Down
6 changes: 1 addition & 5 deletions tools/workspace/clp_internal/package.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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*",
Expand Down Expand Up @@ -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",
Expand Down
9 changes: 3 additions & 6 deletions tools/workspace/default.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down Expand Up @@ -224,10 +223,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:
Expand Down
13 changes: 13 additions & 0 deletions tools/workspace/ipopt/package.BUILD.bazel
Original file line number Diff line number Diff line change
@@ -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,
)
Loading

0 comments on commit 9be0c39

Please sign in to comment.