Skip to content

Commit

Permalink
[solvers] Port solver back-ends to use SpecificOptions
Browse files Browse the repository at this point in the history
In the near future, we anticipate changing the SolverOptions API in
support of loading and saving (i.e., serialization). That's especially
troublesome for our solver back-ends that consume its information,
given the low-level and hodge-podge ways in which they hunt for and
apply their specific options.

This commit introduces a higher-level intermediary between solver
back-ends and the program's options. Now SolverOptions are solely a
user-facing aspect of defining a program; the solver back-ends never
touch SolverOptions anymore. The new SolverBase::DoSolve2 virtual
provides the mechanism for back-ends to take advantage of the new API.
All solvers have been ported to use it. The old API remains intact for
any out-of-tree solvers.

The new API is also designed to improve uniformity of common errors,
such as unknown names or wrongly-typed values.

The new API also lays the groundwork for more efficient processing, as
future work. It removes the need for the "Merge" (copy) operation in
the hot path -- since it only provides a *view* of the options, it can
easily keep track of several dictionaries and query them in order,
with no copying.
  • Loading branch information
jwnimmer-tri committed Apr 26, 2024
1 parent 4d4b497 commit ea392f0
Show file tree
Hide file tree
Showing 47 changed files with 1,175 additions and 765 deletions.
22 changes: 19 additions & 3 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ drake_cc_package_library(
":solver_type_converter",
":sos_basis_generator",
":sparse_and_dense_matrix",
":specific_options",
":unrevised_lemke_solver",
],
)
Expand Down Expand Up @@ -319,6 +320,19 @@ drake_cc_library(
deps = [],
)

drake_cc_library(
name = "specific_options",
srcs = ["specific_options.cc"],
hdrs = ["specific_options.h"],
deps = [
":solver_id",
":solver_options",
"//common:name_value",
"//common:overloaded",
"//common:string_container",
],
)

drake_cc_library(
name = "indeterminate",
srcs = ["indeterminate.cc"],
Expand All @@ -327,7 +341,7 @@ drake_cc_library(
"//common/symbolic:expression",
],
deps = [
"//solvers:decision_variable",
":decision_variable",
],
)

Expand Down Expand Up @@ -725,6 +739,7 @@ drake_cc_library(
interface_deps = [
":mathematical_program",
":solver_interface",
":specific_options",
],
deps = [],
)
Expand Down Expand Up @@ -877,6 +892,7 @@ drake_cc_optional_library(
deps = [
":aggregate_costs_constraints",
":mathematical_program",
":specific_options",
"//math:quadratic_form",
"@mosek",
],
Expand Down Expand Up @@ -920,9 +936,9 @@ drake_cc_variant_library(
":mathematical_program",
],
deps_enabled = [
"@clp_internal//:clp",
"//common:unused",
"//math:autodiff",
"@clp_internal//:clp",
],
)

Expand All @@ -940,9 +956,9 @@ drake_cc_variant_library(
":mathematical_program",
],
deps_enabled = [
"@ipopt",
"//common:unused",
"//math:autodiff",
"@ipopt",
],
)

Expand Down
105 changes: 7 additions & 98 deletions solvers/clarabel_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -148,98 +148,6 @@ void SetSolverDetails(
solver_details->status = SolverStatusToString(clarabel_solution.status);
}

class SettingsConverter {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SettingsConverter);

explicit SettingsConverter(const SolverOptions& solver_options) {
// Propagate Drake's common options into `settings_`.
settings_.verbose = solver_options.get_print_to_console();
// TODO(jwnimmer-tri) Handle get_print_file_name().

// Copy the Clarabel-specific `solver_options` to pending maps.
pending_options_double_ =
solver_options.GetOptionsDouble(ClarabelSolver::id());
pending_options_int_ = solver_options.GetOptionsInt(ClarabelSolver::id());
pending_options_str_ = solver_options.GetOptionsStr(ClarabelSolver::id());

// Move options from `pending_..._` to `settings_`.
Serialize(this, settings_);

// Identify any unsupported names (i.e., any leftovers in `pending_..._`).
std::vector<std::string> unknown_names;
for (const auto& [name, _] : pending_options_double_) {
unknown_names.push_back(name);
}
for (const auto& [name, _] : pending_options_int_) {
unknown_names.push_back(name);
}
for (const auto& [name, _] : pending_options_str_) {
unknown_names.push_back(name);
}
if (unknown_names.size() > 0) {
throw std::logic_error(fmt::format(
"ClarabelSolver: unrecognized solver options {}. Please check "
"https://oxfordcontrol.github.io/ClarabelDocs/stable/api_settings/ "
"for the supported solver options.",
fmt::join(unknown_names, ", ")));
}
}

const clarabel::DefaultSettings<double>& settings() const {
return settings_;
}

void Visit(const NameValue<double>& x) {
this->SetFromDoubleMap(x.name(), x.value());
}
void Visit(const NameValue<bool>& x) {
auto it = pending_options_int_.find(x.name());
if (it != pending_options_int_.end()) {
const int option_value = it->second;
DRAKE_THROW_UNLESS(option_value == 0 || option_value == 1);
}
this->SetFromIntMap(x.name(), x.value());
}
void Visit(const NameValue<uint32_t>& x) {
auto it = pending_options_int_.find(x.name());
if (it != pending_options_int_.end()) {
const int option_value = it->second;
DRAKE_THROW_UNLESS(option_value >= 0);
}
this->SetFromIntMap(x.name(), x.value());
}
void Visit(const NameValue<clarabel::ClarabelDirectSolveMethods>& x) {
DRAKE_THROW_UNLESS(x.name() == std::string{"direct_solve_method"});
// TODO(jwnimmer-tri) Add support for this option.
// For now it is unsupported and will throw (as an unknown name, below).
}

private:
void SetFromDoubleMap(const char* name, double* clarabel_value) {
auto it = pending_options_double_.find(name);
if (it != pending_options_double_.end()) {
*clarabel_value = it->second;
pending_options_double_.erase(it);
}
}
template <typename T>
void SetFromIntMap(const char* name, T* clarabel_value) {
auto it = pending_options_int_.find(name);
if (it != pending_options_int_.end()) {
*clarabel_value = it->second;
pending_options_int_.erase(it);
}
}

std::unordered_map<std::string, double> pending_options_double_;
std::unordered_map<std::string, int> pending_options_int_;
std::unordered_map<std::string, std::string> pending_options_str_;

clarabel::DefaultSettings<double> settings_ =
clarabel::DefaultSettingsBuilder<double>::default_settings().build();
};

// See ParseBoundingBoxConstraints for the meaning of bbcon_dual_indices.
void SetBoundingBoxDualSolution(
const MathematicalProgram& prog,
Expand Down Expand Up @@ -294,10 +202,10 @@ bool ClarabelSolver::is_available() {
return true;
}

void ClarabelSolver::DoSolve(const MathematicalProgram& prog,
const Eigen::VectorXd& initial_guess,
const SolverOptions& merged_options,
MathematicalProgramResult* result) const {
void ClarabelSolver::DoSolve2(const MathematicalProgram& prog,
const Eigen::VectorXd& initial_guess,
internal::SpecificOptions* options,
MathematicalProgramResult* result) const {
if (!prog.GetVariableScaling().empty()) {
static const logging::Warn log_once(
"ClarabelSolver doesn't support the feature of variable scaling.");
Expand Down Expand Up @@ -447,8 +355,9 @@ void ClarabelSolver::DoSolve(const MathematicalProgram& prog,
A.setFromTriplets(A_triplets.begin(), A_triplets.end());
const Eigen::Map<Eigen::VectorXd> b_vec{b.data(), ssize(b)};

const SettingsConverter settings_converter(merged_options);
clarabel::DefaultSettings<double> settings = settings_converter.settings();
clarabel::DefaultSettings<double> settings =
clarabel::DefaultSettingsBuilder<double>::default_settings().build();
options->CopyToSerializableStruct(&settings);

clarabel::DefaultSolver<double> solver(P, q_vec, A, b_vec, cones, settings);

Expand Down
5 changes: 3 additions & 2 deletions solvers/clarabel_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,9 @@ class ClarabelSolver final : public SolverBase {
using SolverBase::Solve;

private:
void DoSolve(const MathematicalProgram&, const Eigen::VectorXd&,
const SolverOptions&, MathematicalProgramResult*) const final;
void DoSolve2(const MathematicalProgram&, const Eigen::VectorXd&,
internal::SpecificOptions*,
MathematicalProgramResult*) const final;
};
} // namespace solvers
} // namespace drake
57 changes: 33 additions & 24 deletions solvers/clp_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -299,38 +299,50 @@ void ParseModelExceptLinearConstraints(
}
}

int ChooseLogLevel(const SolverOptions& options) {
if (options.get_print_to_console()) {
// Documented as "factorizations plus a bit more" in ClpModel.hpp.
return 3;
}
return 0;
struct KnownOptions {
int log_level{0};

// As suggested by the CLP author, we should call scaling() to handle tiny (or
// huge) number in program data. See https://github.com/coin-or/Clp/issues/217
// for the discussion.
int scaling{1};
};

void Serialize(internal::SpecificOptions* archive,
// NOLINTNEXTLINE(runtime/references) to match Serialize concept.
KnownOptions& options) {
archive->Visit(MakeNameValue("log_level", &options.log_level));
archive->Visit(MakeNameValue("scaling", &options.scaling));
}

int ChooseScaling(const SolverOptions& options) {
const auto& clp_options = options.GetOptionsInt(ClpSolver::id());
auto it = clp_options.find("scaling");
if (it == clp_options.end()) {
// Default scaling is 1.
return 1;
} else {
return it->second;
}
KnownOptions ParseOptions(internal::SpecificOptions* options) {
KnownOptions result;
options->Respell([](const auto& common) {
string_unordered_map<SolverOptions::OptionValue> respelled;
// '3' is documented as "factorizations plus a bit more" in ClpModel.hpp.
respelled.emplace("log_level", common.print_to_console ? 3 : 0);
return respelled;
});
options->CopyToSerializableStruct(&result);
return result;
}

} // namespace

bool ClpSolver::is_available() {
return true;
}

void ClpSolver::DoSolve(const MathematicalProgram& prog,
const Eigen::VectorXd& initial_guess,
const SolverOptions& merged_options,
MathematicalProgramResult* result) const {
void ClpSolver::DoSolve2(const MathematicalProgram& prog,
const Eigen::VectorXd& initial_guess,
internal::SpecificOptions* options,
MathematicalProgramResult* result) const {
// TODO(hongkai.dai): use initial guess and more of the merged options.
unused(initial_guess);
const KnownOptions known_options = ParseOptions(options);

ClpSimplex model;
model.setLogLevel(ChooseLogLevel(merged_options));
model.setLogLevel(known_options.log_level);
Eigen::VectorXd xlow(prog.num_vars());
Eigen::VectorXd xupp(prog.num_vars());
Eigen::VectorXd objective_coeff = Eigen::VectorXd::Zero(prog.num_vars());
Expand Down Expand Up @@ -359,10 +371,7 @@ void ClpSolver::DoSolve(const MathematicalProgram& prog,
&bb_con_dual_variable_indices);
}

// As suggested by the CLP author, we should call scaling() to handle tiny (or
// huge) number in program data. See https://github.com/coin-or/Clp/issues/217
// for the discussion.
model.scaling(ChooseScaling(merged_options));
model.scaling(known_options.scaling);

// Solve
model.primal();
Expand Down
5 changes: 3 additions & 2 deletions solvers/clp_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,9 @@ class ClpSolver final : public SolverBase {
using SolverBase::Solve;

private:
void DoSolve(const MathematicalProgram&, const Eigen::VectorXd&,
const SolverOptions&, MathematicalProgramResult*) const final;
void DoSolve2(const MathematicalProgram&, const Eigen::VectorXd&,
internal::SpecificOptions*,
MathematicalProgramResult*) const final;
};
} // namespace solvers
} // namespace drake
11 changes: 11 additions & 0 deletions solvers/common_solver_option.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <ostream>
#include <string>

#include "drake/common/fmt_ostream.h"

Expand Down Expand Up @@ -31,6 +32,16 @@ enum class CommonSolverOption {

std::ostream& operator<<(std::ostream& os,
CommonSolverOption common_solver_option);

namespace internal {

/* Aggregated values for CommonSolverOption, for Drake-internal use only. */
struct CommonSolverOptionValues {
std::string print_file_name;
bool print_to_console{false};
};

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

Expand Down

0 comments on commit ea392f0

Please sign in to comment.