Skip to content

Commit

Permalink
[solvers] Add common option for max number of threads (#21857)
Browse files Browse the repository at this point in the history
Co-authored-by: Jeremy Nimmer <[email protected]>
  • Loading branch information
AlexandreAmice and jwnimmer-tri authored Sep 12, 2024
1 parent 189bc48 commit 59a15c3
Show file tree
Hide file tree
Showing 21 changed files with 240 additions and 40 deletions.
1 change: 1 addition & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -968,6 +968,7 @@ drake_cc_googletest(
deps = [
":find_cache",
":temp_directory",
"//common/test_utilities:set_env",
],
)

Expand Down
32 changes: 3 additions & 29 deletions common/test/find_cache_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,41 +8,15 @@

#include "drake/common/drake_assert.h"
#include "drake/common/temp_directory.h"
#include "drake/common/test_utilities/set_env.h"

namespace drake {
namespace internal {
namespace {

namespace fs = std::filesystem;
using test::SetEnv;

/* RAII to temporarily change an environment variable. */
class SetEnv {
public:
SetEnv(const std::string& var_name, std::optional<std::string> var_value)
: var_name_(var_name) {
const char* orig = std::getenv(var_name.c_str());
if (orig != nullptr) {
orig_value_ = orig;
}
if (var_value.has_value()) {
::setenv(var_name.c_str(), var_value->c_str(), 1);
} else {
::unsetenv(var_name.c_str());
}
}

~SetEnv() {
if (orig_value_.has_value()) {
::setenv(var_name_.c_str(), orig_value_->c_str(), 1);
} else {
::unsetenv(var_name_.c_str());
}
}

private:
std::string var_name_;
std::optional<std::string> orig_value_;
};
namespace fs = std::filesystem;

// Check the TEST_TMPDIR case.
GTEST_TEST(FindCacheTest, TestTmpdir) {
Expand Down
7 changes: 7 additions & 0 deletions common/test_utilities/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ drake_cc_package_library(
":maybe_pause_for_user",
":measure_execution",
":random_polynomial_matrix",
":set_env",
":symbolic_test_util",
],
)
Expand Down Expand Up @@ -138,6 +139,12 @@ drake_cc_library(
],
)

drake_cc_library(
name = "set_env",
testonly = 1,
hdrs = ["set_env.h"],
)

drake_cc_library(
name = "symbolic_test_util",
testonly = 1,
Expand Down
39 changes: 39 additions & 0 deletions common/test_utilities/set_env.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
#pragma once

#include <optional>
#include <string>

namespace drake {
namespace test {

/* RAII to temporarily change an environment variable. */
class SetEnv {
public:
SetEnv(const std::string& var_name, std::optional<std::string> var_value)
: var_name_(var_name) {
const char* orig = std::getenv(var_name.c_str());
if (orig != nullptr) {
orig_value_ = orig;
}
if (var_value.has_value()) {
::setenv(var_name.c_str(), var_value->c_str(), 1);
} else {
::unsetenv(var_name.c_str());
}
}

~SetEnv() {
if (orig_value_.has_value()) {
::setenv(var_name_.c_str(), orig_value_->c_str(), 1);
} else {
::unsetenv(var_name_.c_str());
}
}

private:
std::string var_name_;
std::optional<std::string> orig_value_;
};

} // namespace test
} // namespace drake
6 changes: 6 additions & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -808,6 +808,7 @@ drake_cc_variant_library(
implementation_deps_enabled = [
":gurobi_solver_internal",
"//common:find_resource",
"//common:parallelism",
"//common:scope_exit",
"//common:scoped_singleton",
"//math:eigen_sparse_triplet",
Expand Down Expand Up @@ -865,6 +866,7 @@ drake_cc_optional_library(
implementation_deps = [
":aggregate_costs_constraints",
":mathematical_program",
"//common:parallelism",
"//math:quadratic_form",
"@mosek",
],
Expand Down Expand Up @@ -1383,6 +1385,7 @@ drake_cc_optional_googletest(

drake_cc_googletest(
name = "gurobi_solver_test",
num_threads = 2,
tags = gurobi_test_tags(),
use_default_main = False,
deps = [
Expand All @@ -1394,9 +1397,11 @@ drake_cc_googletest(
":mixed_integer_optimization_util",
":quadratic_program_examples",
":second_order_cone_program_examples",
"//common:add_text_logging_gflags",
"//common:temp_directory",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
"//common/test_utilities:set_env",
],
)

Expand Down Expand Up @@ -2011,6 +2016,7 @@ drake_cc_googletest(

drake_cc_googletest(
name = "solver_options_test",
num_threads = 2,
deps = [
":solver_options",
"//common/test_utilities:expect_no_throw",
Expand Down
3 changes: 3 additions & 0 deletions solvers/clarabel_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,9 @@ class SettingsConverter {
settings_.verbose = solver_options.get_print_to_console();
// TODO(jwnimmer-tri) Handle get_print_file_name().

// Clarabel does not support setting the number of threads so we ignore
// the kMaxNumThreads option.

// Copy the Clarabel-specific `solver_options` to pending maps.
pending_options_double_ =
solver_options.GetOptionsDouble(ClarabelSolver::id());
Expand Down
3 changes: 3 additions & 0 deletions solvers/clp_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -364,6 +364,9 @@ void ClpSolver::DoSolve(const MathematicalProgram& prog,
// for the discussion.
model.scaling(ChooseScaling(merged_options));

// CLP Simplex solver does not support multithreaded solves so we can ignore
// the kMaxNumThreads option.

// Solve
model.primal();

Expand Down
3 changes: 3 additions & 0 deletions solvers/common_solver_option.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ std::ostream& operator<<(std::ostream& os,
case CommonSolverOption::kStandaloneReproductionFileName:
os << "kStandaloneReproductionFileName";
return os;
case CommonSolverOption::kMaxThreads:
os << "kMaxThreads";
return os;
default:
DRAKE_UNREACHABLE();
}
Expand Down
15 changes: 15 additions & 0 deletions solvers/common_solver_option.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,21 @@ enum class CommonSolverOption {
* empty string "" indicates that no file should be written.
*/
kStandaloneReproductionFileName,
/** Many solvers are multi-threaded. The user can request the maximum number
* of threads used by the solver with this `int` option. When not set, the
* value defaults to Parallelism.Max().num_threads(), which can be controlled
* via the \ref drake::Parallelism "DRAKE_NUM_THREADS" environment variable.
*
* @pre The number of threads must be greater than 0.
* @note Setting this value higher than the actual hardware concurrency may
* result in a degraded performance. It is recommended to set this value lower
* than or equal to Parallelism.Max().num_threads().
* @note A solver may choose to use fewer threads than the value specified.
* @note This options does NOT disable multi-threading in BLAS/LAPACK which is
* used by many solvers under the hood. Therefore, some internal operations of
* the solvers may still be multi-core.
*/
kMaxThreads,
};

std::ostream& operator<<(std::ostream& os,
Expand Down
2 changes: 2 additions & 0 deletions solvers/csdp_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -412,6 +412,8 @@ std::string MaybeWriteCsdpParams(const SolverOptions& options) {
if (options.get_print_to_console()) {
all_csdp_params += "printlevel=1\n";
}
// CSDP does not support setting the number of threads so we ignore
// the kMaxNumThreads option.

// Add the specific options next (so they trump the common options).
for (const auto& [key, value] : options.GetOptionsInt(CsdpSolver::id())) {
Expand Down
35 changes: 27 additions & 8 deletions solvers/gurobi_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@

#include "drake/common/drake_assert.h"
#include "drake/common/find_resource.h"
#include "drake/common/parallelism.h"
#include "drake/common/scope_exit.h"
#include "drake/common/scoped_singleton.h"
#include "drake/common/text_logging.h"
Expand Down Expand Up @@ -949,22 +950,39 @@ void GurobiSolver::DoSolve(const MathematicalProgram& prog,
SetOptionOrThrow(model_env, "LogToConsole",
static_cast<int>(merged_options.get_print_to_console()));
}

// Default the option for number of threads based on an environment variable
// (but only if the user hasn't set the option directly already).
if (!merged_options.GetOptionsInt(id()).contains("Threads")) {
// Here's our priority order for selecting the number of threads:
// - Gurobi-specific solver option "Threads"
// - The value of CommonSolverOptions::kMaxThreads if set.
// - GUROBI_NUM_THREADS environment variable.
// - Drake's maximum parallelism.
std::optional<int> num_threads = std::nullopt;
if (merged_options.GetOptionsInt(id()).contains("Threads")) {
num_threads = merged_options.GetOptionsInt(id()).at("Threads");
}
if (!num_threads.has_value()) {
// If unset, check CommonSolverOptions::kMaxThreads.
num_threads = merged_options.get_max_threads();
}
if (!num_threads.has_value()) {
// If unset, use GUROBI_NUM_THREADS. We attempt to read the value of
// GUROBI_NUM_THREADS and warn the user if it is not parseable.
if (char* num_threads_str = std::getenv("GUROBI_NUM_THREADS")) {
const std::optional<int> num_threads = ParseInt(num_threads_str);
num_threads = ParseInt(num_threads_str);
if (num_threads.has_value()) {
SetOptionOrThrow(model_env, "Threads", *num_threads);
log()->debug("Using GUROBI_NUM_THREADS={}", *num_threads);
log()->debug("Using GUROBI_NUM_THREADS={}", num_threads.value());
} else {
static const logging::Warn log_once(
"Ignoring unparseable value '{}' for GUROBI_NUM_THREADS",
num_threads_str);
}
}
}
if (!num_threads.has_value()) {
// If unset, use max parallelism.
num_threads = Parallelism::Max().num_threads();
}
DRAKE_DEMAND(num_threads.has_value());
SetOptionOrThrow(model_env, "Threads", num_threads.value());

for (const auto& it : merged_options.GetOptionsDouble(id())) {
if (!error) {
Expand Down Expand Up @@ -1076,7 +1094,8 @@ void GurobiSolver::DoSolve(const MathematicalProgram& prog,
GRBgeterrormsg(env));
solver_details.error_code = error;
} else {
// Always set the primal and dual solution for any non-error gurobi status.
// Always set the primal and dual solution for any non-error gurobi
// status.
SetSolution(model, model_env, prog, is_new_variable, num_prog_vars, is_mip,
num_gurobi_linear_constraints, constant_cost,
constraint_dual_start_row, bb_con_dual_indices, result,
Expand Down
14 changes: 12 additions & 2 deletions solvers/gurobi_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,19 @@ struct GurobiSolverDetails {
/// setting GRBwrite to "FILENAME.ilp" to write IIS to a file with extension
/// "ilp". Default is not to compute IIS.
///
/// If the "Threads" integer solver option has not been set by the user, then
/// %GurobiSolver uses environment variable GUROBI_NUM_THREADS (if set) as a
/// GurobiSolver supports parallelization during Solve().
/// If both the "Threads" integer solver option and
/// CommonSolverOption::kMaxThreads have been set by the user, then the value in
/// "Threads" will be used as the number of threads.
///
/// If neither the "Threads" integer solver option nor
/// CommonSolverOption::kMaxThreads has been set by the user, then
/// %GurobiSolver uses the environment variable GUROBI_NUM_THREADS (if set) as a
/// default value for "Threads".
///
/// If none of "Threads",
/// CommonSolverOption::kMaxThreads, or GUROBI_NUM_THREADS are set, then
/// Drake's default maximum parallelism will be used.
class GurobiSolver final : public SolverBase {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(GurobiSolver);
Expand Down
3 changes: 3 additions & 0 deletions solvers/ipopt_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,9 @@ void SetAppOptions(const SolverOptions& options, Ipopt::IpoptApplication* app) {
app->Options()->SetIntegerValue("file_print_level", verbose_level);
}

// IPOPT does not support setting the number of threads so we ignore
// the kMaxNumThreads option.

// The solver-specific options will trump our defaults.
const SolverId self = IpoptSolver::id();
for (const auto& [name, value] : options.GetOptionsDouble(self)) {
Expand Down
7 changes: 7 additions & 0 deletions solvers/mosek_solver_internal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

#include "drake/common/fmt_ostream.h"
#include "drake/common/never_destroyed.h"
#include "drake/common/parallelism.h"
#include "drake/math/quadratic_form.h"
#include "drake/solvers/aggregate_costs_constraints.h"

Expand Down Expand Up @@ -1497,6 +1498,12 @@ MSKrescodee MosekSolverProgram::UpdateOptions(
bool* print_to_console, std::string* print_file_name,
std::optional<std::string>* msk_writedata) {
MSKrescodee rescode{MSK_RES_OK};
// Set the maximum number of threads used by Mosek via the CommonSolverOptions
// first, so that solver-specific options can overwrite this later.
const int num_threads = merged_options.get_max_threads().value_or(
Parallelism::Max().num_threads());
rescode = MSK_putnaintparam(task_, "MSK_IPAR_NUM_THREADS", num_threads);
ThrowForInvalidOption(rescode, "MSK_IPAR_NUM_THREADS", num_threads);
for (const auto& double_options : merged_options.GetOptionsDouble(mosek_id)) {
if (rescode == MSK_RES_OK) {
rescode = MSK_putnadouparam(task_, double_options.first.c_str(),
Expand Down
4 changes: 4 additions & 0 deletions solvers/osqp_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -240,6 +240,10 @@ void SetOsqpSolverSettings(const SolverOptions& solver_options,
int verbose_console = solver_options.get_print_to_console() != 0;
SetOsqpSolverSettingWithDefaultValue(options_int, "verbose",
&(settings->verbose), verbose_console);

// OSQP does not support setting the number of threads so we ignore
// the kMaxNumThreads option.

SetOsqpSolverSetting(options_int, "scaled_termination",
&(settings->scaled_termination));
SetOsqpSolverSetting(options_int, "check_termination",
Expand Down
2 changes: 2 additions & 0 deletions solvers/scs_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -607,6 +607,8 @@ void ScsSolver::DoSolve(const MathematicalProgram& prog,
SetScsSettings(&input_solver_options_int,
merged_options.get_print_to_console(), scs_stgs);
SetScsSettings(&input_solver_options_double, scs_stgs);
// SCS does not support setting the number of threads so we ignore
// the kMaxNumThreads option.

ScsInfo scs_info{0};

Expand Down
2 changes: 2 additions & 0 deletions solvers/snopt_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1429,6 +1429,8 @@ void SnoptSolver::DoSolve(const MathematicalProgram& prog,
int_options[kTimingLevel] = 0;
}

// SNOPT does not support setting the number of threads so we ignore
// the kMaxNumThreads option.
SolveWithGivenOptions(prog, initial_guess, merged_options.GetOptionsStr(id()),
int_options, merged_options.GetOptionsDouble(id()),
merged_options.get_print_file_name(), result);
Expand Down
Loading

0 comments on commit 59a15c3

Please sign in to comment.