Stores options for multiple solvers.
This interface does not do any verification of solver parameters. It does not even verify that the specified solver exists. Use this only when you have particular knowledge of what solver is being invoked, and exactly what tuning is required.
Supported solver names/options:
"SNOPT" – Parameter names and values as specified in SNOPT User's Guide section 7.7 "Description of the optional parameters", used as described in section 7.5 for snSet(). The SNOPT user guide can be obtained from https://web.stanford.edu/group/SOL/guides/sndoc7.pdf
"IPOPT" – Parameter names and values as specified in IPOPT users guide section "Options Reference" https://coin-or.github.io/Ipopt/OPTIONS.html
"NLOPT" – Parameter names and values are specified in https://nlopt.readthedocs.io/en/latest/NLopt_C-plus-plus_Reference/ (in the Stopping criteria section). Besides these parameters, the user can specify "algorithm" using a string of the algorithm name. The complete set of algorithms is listed in "nlopt_algorithm_to_string()" function in github.com/stevengj/nlopt/blob/master/src/api/general.c. If you would like to use certain algorithm, for example NLOPT_LD_SLSQP, call SetOption(NloptSolver::id(), NloptSolver::AlgorithmName(), "LD_SLSQP");
"GUROBI" – Parameter name and values as specified in Gurobi Reference Manual, section 10.2 "Parameter Descriptions" https://www.gurobi.com/documentation/10.0/refman/parameters.html
"SCS" – Parameter name and values as specified in the struct SCS_SETTINGS in SCS header file https://github.com/cvxgrp/scs/blob/master/include/scs.h Note that the SCS code on github master might be more up-to-date than the version used in Drake.
"MOSEK™" – Parameter name and values as specified in Mosek Reference https://docs.mosek.com/9.3/capi/parameters.html
"OSQP" – Parameter name and values as specified in OSQP Reference https://osqp.org/docs/interfaces/solver_settings.html#solver-settings
"Clarabel" – Parameter name and values as specified in Clarabel https://oxfordcontrol.github.io/ClarabelDocs/stable/api_settings/ Note that direct_solve_method
is not supported in Drake yet. Clarabel's boolean options should be passed as integers (0 or 1).
"CSDP" – Parameter name and values as specified at https://manpages.ubuntu.com/manpages/focal/en/man1/csdp-randgraph.1.html
#include <drake/solvers/solver_options.h>
Public Types | |
using | OptionValue = std::variant< double, int, std::string > |
The values stored in SolverOptions can be double, int, or string. More... | |
Public Member Functions | |
void | SetOption (const SolverId &solver_id, std::string key, OptionValue value) |
Sets a solver option for a specific solver. More... | |
void | SetOption (CommonSolverOption key, OptionValue value) |
Sets a common option for all solvers supporting that option (for example, printing the progress in each iteration). More... | |
void | Merge (const SolverOptions &other) |
Merges the other solver options into this. More... | |
bool | operator== (const SolverOptions &other) const |
bool | operator!= (const SolverOptions &other) const |
std::string | to_string () const |
template<typename Archive > | |
void | Serialize (Archive *a) |
Passes this object to an Archive. More... | |
std::unordered_map< std::string, double > | GetOptionsDouble (const SolverId &solver_id) const |
(Deprecated.) More... | |
std::unordered_map< std::string, int > | GetOptionsInt (const SolverId &solver_id) const |
(Deprecated.) More... | |
std::unordered_map< std::string, std::string > | GetOptionsStr (const SolverId &solver_id) const |
(Deprecated.) More... | |
std::unordered_map< CommonSolverOption, OptionValue > | common_solver_options () const |
(Deprecated.) More... | |
std::string | get_print_file_name () const |
(Deprecated.) More... | |
bool | get_print_to_console () const |
(Deprecated.) More... | |
std::string | get_standalone_reproduction_file_name () const |
(Deprecated.) More... | |
std::optional< int > | get_max_threads () const |
(Deprecated.) More... | |
template<typename T > | |
std::unordered_map< std::string, T > | GetOptions (const SolverId &solver_id) const |
(Deprecated.) More... | |
std::unordered_set< SolverId > | GetSolverIds () const |
(Deprecated.) More... | |
void | CheckOptionKeysForSolver (const SolverId &solver_id, const std::unordered_set< std::string > &allowable_double_keys, const std::unordered_set< std::string > &allowable_int_keys, const std::unordered_set< std::string > &allowable_str_keys) const |
(Deprecated.) More... | |
Public Attributes | |
string_unordered_map< string_unordered_map< OptionValue > > | options |
The options are indexed first by the solver name and second by the key. More... | |
using OptionValue = std::variant<double, int, std::string> |
The values stored in SolverOptions can be double, int, or string.
In the future, we might re-order or add more allowed types without any deprecation period, so be sure to use std::visit or std::get<T> to retrieve the variant's value in a future-proof way.
void CheckOptionKeysForSolver | ( | const SolverId & | solver_id, |
const std::unordered_set< std::string > & | allowable_double_keys, | ||
const std::unordered_set< std::string > & | allowable_int_keys, | ||
const std::unordered_set< std::string > & | allowable_str_keys | ||
) | const |
(Deprecated.)
std::unordered_map<CommonSolverOption, OptionValue> common_solver_options | ( | ) | const |
(Deprecated.)
std::optional<int> get_max_threads | ( | ) | const |
(Deprecated.)
std::string get_print_file_name | ( | ) | const |
(Deprecated.)
bool get_print_to_console | ( | ) | const |
(Deprecated.)
std::string get_standalone_reproduction_file_name | ( | ) | const |
(Deprecated.)
std::unordered_map<std::string, T> GetOptions | ( | const SolverId & | solver_id | ) | const |
(Deprecated.)
(Deprecated.)
(Deprecated.)
std::unordered_map<std::string, std::string> GetOptionsStr | ( | const SolverId & | solver_id | ) | const |
(Deprecated.)
std::unordered_set<SolverId> GetSolverIds | ( | ) | const |
(Deprecated.)
void Merge | ( | const SolverOptions & | other | ) |
Merges the other solver options into this.
If other
and this
option both define the same option for the same solver, we ignore the one from other
and keep the one from this
.
bool operator!= | ( | const SolverOptions & | other | ) | const |
bool operator== | ( | const SolverOptions & | other | ) | const |
void Serialize | ( | Archive * | a | ) |
Passes this object to an Archive.
Refer to YAML Serialization for background.
void SetOption | ( | const SolverId & | solver_id, |
std::string | key, | ||
OptionValue | value | ||
) |
Sets a solver option for a specific solver.
If the solver doesn't support the option, it will throw an exception during the Solve (not when setting the option here).
void SetOption | ( | CommonSolverOption | key, |
OptionValue | value | ||
) |
Sets a common option for all solvers supporting that option (for example, printing the progress in each iteration).
If the solver doesn't support the option, the option is ignored.
std::string to_string | ( | ) | const |
string_unordered_map<string_unordered_map<OptionValue> > options |
The options are indexed first by the solver name and second by the key.
In the case of Drake's common options, the solver name is "Drake".