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 | |
SolverOptions ()=default | |
void | SetOption (const SolverId &solver_id, const std::string &solver_option, double option_value) |
Sets a double-valued solver option for a specific solver. More... | |
void | SetOption (const SolverId &solver_id, const std::string &solver_option, int option_value) |
Sets an integer-valued solver option for a specific solver. More... | |
void | SetOption (const SolverId &solver_id, const std::string &solver_option, const std::string &option_value) |
Sets a string-valued 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... | |
const std::unordered_map< std::string, double > & | GetOptionsDouble (const SolverId &solver_id) const |
const std::unordered_map< std::string, int > & | GetOptionsInt (const SolverId &solver_id) const |
const std::unordered_map< std::string, std::string > & | GetOptionsStr (const SolverId &solver_id) const |
const std::unordered_map< CommonSolverOption, OptionValue > & | common_solver_options () const |
Gets the common options for all solvers. More... | |
std::string | get_print_file_name () const |
Returns the kPrintFileName set via CommonSolverOption, or else an empty string if the option has not been set. More... | |
bool | get_print_to_console () const |
Returns the kPrintToConsole set via CommonSolverOption, or else false if the option has not been set. More... | |
std::string | get_standalone_reproduction_file_name () const |
Returns the kStandaloneReproductionFileName set via CommonSolverOption, or else an empty string if the option has not been set. More... | |
std::optional< int > | get_max_threads () const |
Returns the kMaxThreads set via CommonSolverOption. More... | |
template<typename T > | |
const std::unordered_map< std::string, T > & | GetOptions (const SolverId &solver_id) const |
std::unordered_set< SolverId > | GetSolverIds () const |
Returns the IDs that have any option set. More... | |
void | Merge (const SolverOptions &other) |
Merges the other solver options into this. More... | |
bool | operator== (const SolverOptions &other) const |
Returns true if this and other have exactly the same solvers, with exactly the same keys and values for the options for each solver. More... | |
bool | operator!= (const SolverOptions &other) const |
Negate operator==. 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 |
Check if for a given solver_id, the option keys are included in double_keys, int_keys and str_keys. More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
SolverOptions (const SolverOptions &)=default | |
SolverOptions & | operator= (const SolverOptions &)=default |
SolverOptions (SolverOptions &&)=default | |
SolverOptions & | operator= (SolverOptions &&)=default |
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.
|
default |
|
default |
|
default |
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 |
Check if for a given solver_id, the option keys are included in double_keys, int_keys and str_keys.
solver_id | If this SolverOptions has set options for this solver_id, then we check if the option keys are a subset of double_keys , int_keys and str_keys . |
double_keys | The set of allowable keys for double options. |
int_keys | The set of allowable keys for int options. |
str_keys | The set of allowable keys for string options. |
std::exception | if the solver contains un-allowed options. |
const std::unordered_map<CommonSolverOption, OptionValue>& common_solver_options | ( | ) | const |
Gets the common options for all solvers.
Refer to CommonSolverOption for more details.
std::optional<int> get_max_threads | ( | ) | const |
Returns the kMaxThreads set via CommonSolverOption.
Returns nullopt if kMaxThreads is unset.
std::string get_print_file_name | ( | ) | const |
Returns the kPrintFileName set via CommonSolverOption, or else an empty string if the option has not been set.
bool get_print_to_console | ( | ) | const |
Returns the kPrintToConsole set via CommonSolverOption, or else false if the option has not been set.
std::string get_standalone_reproduction_file_name | ( | ) | const |
Returns the kStandaloneReproductionFileName set via CommonSolverOption, or else an empty string if the option has not been set.
const std::unordered_map<std::string, T>& GetOptions | ( | const SolverId & | solver_id | ) | const |
const std::unordered_map<std::string, std::string>& GetOptionsStr | ( | const SolverId & | solver_id | ) | const |
std::unordered_set<SolverId> GetSolverIds | ( | ) | const |
Returns the IDs that have any option set.
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 then one from other
and keep the one from this
.
bool operator!= | ( | const SolverOptions & | other | ) | const |
Negate operator==.
|
default |
|
default |
bool operator== | ( | const SolverOptions & | other | ) | const |
Returns true if this
and other
have exactly the same solvers, with exactly the same keys and values for the options for each solver.
void SetOption | ( | const SolverId & | solver_id, |
const std::string & | solver_option, | ||
double | option_value | ||
) |
Sets a double-valued solver option for a specific solver.
Sets an integer-valued solver option for a specific solver.
void SetOption | ( | const SolverId & | solver_id, |
const std::string & | solver_option, | ||
const std::string & | option_value | ||
) |
Sets a string-valued solver option for a specific solver.
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.