Skip to content

Commit

Permalink
[solvers] IpoptSolver doesn't hard-code the linear solver (RobotLocom…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored and RussTedrake committed Dec 15, 2024
1 parent 69fed1d commit 8f083f9
Show file tree
Hide file tree
Showing 6 changed files with 68 additions and 12 deletions.
14 changes: 13 additions & 1 deletion solvers/ipopt_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,9 @@ void SetAppOptions(const std::string& default_linear_solver,
// Turn off the banner.
set_string_option("sb", "yes");

set_string_option("linear_solver", default_linear_solver);
if (!default_linear_solver.empty()) {
set_string_option("linear_solver", default_linear_solver);
}

// The default tolerance.
const double tol = 1.05e-10; // Note: SNOPT is only 1e-6, but in #3712 we
Expand Down Expand Up @@ -147,6 +149,16 @@ const char* IpoptSolverDetails::ConvertStatusToString() const {
return "Unknown enumerated SolverReturn value.";
}

IpoptSolver::IpoptSolver()
: SolverBase(id(), &is_available, &is_enabled,
&ProgramAttributesSatisfied) {
const std::vector<std::string_view> linear_solvers =
internal::GetSupportedIpoptLinearSolvers();
if (!linear_solvers.empty()) {
default_linear_solver_ = linear_solvers.at(0);
}
}

bool IpoptSolver::is_available() {
return true;
}
Expand Down
11 changes: 0 additions & 11 deletions solvers/ipopt_solver_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,17 +8,6 @@
namespace drake {
namespace solvers {

IpoptSolver::IpoptSolver()
: SolverBase(id(), &is_available, &is_enabled, &ProgramAttributesSatisfied),
// The default linear solver is MA27, but it is not freely redistributable
// so we cannot use it. MUMPS is the only compatible linear solver
// guaranteed to be available on both macOS and Ubuntu. In versions of
// IPOPT prior to 3.13, it would correctly determine that MUMPS was the
// only available solver, but its behavior changed to instead error having
// unsuccessfully tried to dlopen a nonexistent hsl library that would
// contain MA27.
default_linear_solver_("mumps") {}

IpoptSolver::~IpoptSolver() = default;

void IpoptSolver::SetDefaultLinearSolver(std::string linear_solver) {
Expand Down
23 changes: 23 additions & 0 deletions solvers/ipopt_solver_internal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include <limits>
#include <optional>

#include <IpLinearSolvers.h>

#include "drake/common/text_logging.h"

using Ipopt::Index;
Expand Down Expand Up @@ -761,6 +763,27 @@ void IpoptSolver_NLP::EvaluateConstraints(Index n, const Number* x,
constraint_cache_->grad_valid = true;
}
}

std::vector<std::string_view> GetSupportedIpoptLinearSolvers() {
std::vector<std::string_view> result;
// IPOPT's upstream default linear solver is MA27, but it is not freely
// redistributable so Drake cannot use it. In Drake's Ubuntu and macOS build
// recipes for IPOPT, one or both of MUMPS or SPRAL linear solvers will be
// available. We'll ask IPOPT which of those two linear solver(s) have been
// built into Drake.
const IpoptLinearSolver solver_mask =
IpoptGetAvailableLinearSolvers(/* buildinonly = */ 1);
// The first item in the result will be Drake's default linear solver.
// We'll prefer MUMPS because it has been our traditional choice.
if (solver_mask & IPOPTLINEARSOLVER_MUMPS) {
result.emplace_back("mumps");
}
if (solver_mask & IPOPTLINEARSOLVER_SPRAL) {
result.emplace_back("spral");
}
return result;
}

} // namespace internal
} // namespace solvers
} // namespace drake
7 changes: 7 additions & 0 deletions solvers/ipopt_solver_internal.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
// that we can expose the internals to ipopt_solver_internal_test.

#include <memory>
#include <string_view>
#include <unordered_map>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -143,6 +144,12 @@ class DRAKE_NO_EXPORT IpoptSolver_NLP : public Ipopt::TNLP {
// corresponding dual variables.
std::unordered_map<Binding<Constraint>, int> constraint_dual_start_index_;
};

// Returns Drake's supported values for the "linear_solver" IpoptSolver option.
// This will be affected by which options the IPOPT library was compiled with.
// The first item in the result is Drake's default value.
std::vector<std::string_view> GetSupportedIpoptLinearSolvers();

} // namespace internal
} // namespace solvers
} // namespace drake
4 changes: 4 additions & 0 deletions solvers/no_ipopt.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@ const char* IpoptSolverDetails::ConvertStatusToString() const {
"solver.");
}

IpoptSolver::IpoptSolver()
: SolverBase(id(), &is_available, &is_enabled,
&ProgramAttributesSatisfied) {}

bool IpoptSolver::is_available() {
return false;
}
Expand Down
21 changes: 21 additions & 0 deletions solvers/test/ipopt_solver_internal_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -270,6 +270,27 @@ GTEST_TEST(TestIpoptSolverNlp, NonlinearConstraintDuplicatedVariables) {
EXPECT_TRUE(CompareMatrices(jac.toDense(), jac_expected));
}
}

#if defined(__APPLE__)
constexpr bool kApple = true;
#else
constexpr bool kApple = false;
#endif

// This provides a cross-check of our build system choices for @ipopt.
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");
} else {
expected.emplace_back("mumps");
expected.emplace_back("spral");
}
EXPECT_EQ(actual, expected);
}

} // namespace internal
} // namespace solvers
} // namespace drake

0 comments on commit 8f083f9

Please sign in to comment.