diff --git a/bindings/pydrake/solvers/solvers_py_options.cc b/bindings/pydrake/solvers/solvers_py_options.cc index 28e113284827..e3ea4fe65993 100644 --- a/bindings/pydrake/solvers/solvers_py_options.cc +++ b/bindings/pydrake/solvers/solvers_py_options.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/deprecation_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/pydrake_pybind.h" #include "drake/bindings/pydrake/solvers/solvers_py.h" @@ -33,26 +34,15 @@ void DefineSolversOptions(py::module m) { cls // BR .def(py::init<>(), doc.SolverOptions.ctor.doc) .def("SetOption", - py::overload_cast( - &SolverOptions::SetOption), - py::arg("solver_id"), py::arg("solver_option"), - py::arg("option_value"), - doc.SolverOptions.SetOption.doc_double_option) - .def("SetOption", - py::overload_cast( - &SolverOptions::SetOption), - py::arg("solver_id"), py::arg("solver_option"), - py::arg("option_value"), doc.SolverOptions.SetOption.doc_int_option) - .def("SetOption", - py::overload_cast(&SolverOptions::SetOption), - py::arg("solver_id"), py::arg("solver_option"), - py::arg("option_value"), doc.SolverOptions.SetOption.doc_str_option) + py::overload_cast(&SolverOptions::SetOption), + py::arg("solver_id"), py::arg("key"), py::arg("value"), + doc.SolverOptions.SetOption.doc_3args) .def("SetOption", py::overload_cast( &SolverOptions::SetOption), py::arg("key"), py::arg("value"), - doc.SolverOptions.SetOption.doc_common_option) + doc.SolverOptions.SetOption.doc_2args) .def( "GetOptions", [](const SolverOptions& solver_options, SolverId solver_id) { @@ -82,6 +72,39 @@ void DefineSolversOptions(py::module m) { return ""; }); DefCopyAndDeepCopy(&cls); + + constexpr char kSetOptionKwargNameDeprecation[] = + "The kwarg names for SolverOptions.SetOption have changed; the new " + "names are `key` and `value` not `solver_option` and `option_value`; " + "the old names are deprecated and will be removed from Drake on or " + "after 2025-05-01."; + // Deprecated 2025-05. + cls // BR + .def("SetOption", + WrapDeprecated(kSetOptionKwargNameDeprecation, + [](SolverOptions& self, const SolverId& solver_id, + const std::string& solver_option, double option_value) { + self.SetOption(solver_id, solver_option, option_value); + }), + py::arg("solver_id"), py::arg("solver_option"), + py::arg("option_value"), kSetOptionKwargNameDeprecation) + .def("SetOption", + WrapDeprecated(kSetOptionKwargNameDeprecation, + [](SolverOptions& self, const SolverId& solver_id, + const std::string& solver_option, int option_value) { + self.SetOption(solver_id, solver_option, option_value); + }), + py::arg("solver_id"), py::arg("solver_option"), + py::arg("option_value"), kSetOptionKwargNameDeprecation) + .def("SetOption", + WrapDeprecated(kSetOptionKwargNameDeprecation, + [](SolverOptions& self, const SolverId& solver_id, + const std::string& solver_option, + const std::string& option_value) { + self.SetOption(solver_id, solver_option, option_value); + }), + py::arg("solver_id"), py::arg("solver_option"), + py::arg("option_value"), kSetOptionKwargNameDeprecation); } } diff --git a/bindings/pydrake/solvers/test/mathematicalprogram_test.py b/bindings/pydrake/solvers/test/mathematicalprogram_test.py index 957e296761e1..58262960d71a 100644 --- a/bindings/pydrake/solvers/test/mathematicalprogram_test.py +++ b/bindings/pydrake/solvers/test/mathematicalprogram_test.py @@ -9,6 +9,7 @@ from pydrake.autodiffutils import AutoDiffXd from pydrake.common import kDrakeAssertIsArmed, Parallelism from pydrake.common.test_utilities import numpy_compare +from pydrake.common.test_utilities.deprecation import catch_drake_warnings from pydrake.forwarddiff import jacobian from pydrake.math import ge from pydrake.solvers import ( @@ -1326,14 +1327,26 @@ def test_solver_options(self): CSO = mp.CommonSolverOption dut = SolverOptions() solver_id = SolverId("dummy") - dut.SetOption(solver_id, "float_key", 1.0) - dut.SetOption(solver_id, "int_key", 2) - dut.SetOption(solver_id, "str_key", "3") + dut.SetOption(solver_id=solver_id, key="float_key", value=1.0) + dut.SetOption(solver_id=solver_id, key="int_key", value=2) + dut.SetOption(solver_id=solver_id, key="str_key", value="3") + with catch_drake_warnings(expected_count=1): + dut.SetOption(solver_id=solver_id, solver_option="dep_float_key", + option_value=4.0) + with catch_drake_warnings(expected_count=1): + dut.SetOption(solver_id=solver_id, solver_option="dep_int_key", + option_value=5) + with catch_drake_warnings(expected_count=1): + dut.SetOption(solver_id=solver_id, solver_option="dep_str_key", + option_value="6") dut.SetOption(CSO.kPrintToConsole, True) dut.SetOption(CSO.kPrintFileName, "print.log") dut.SetOption(CSO.kStandaloneReproductionFileName, "repro.txt") dut.SetOption(CSO.kMaxThreads, 4) - expected_dummy = {"float_key": 1.0, "int_key": 2, "str_key": "3"} + expected_dummy = { + "float_key": 1.0, "int_key": 2, "str_key": "3", + "dep_float_key": 4.0, "dep_int_key": 5, "dep_str_key": "6", + } expected_common = { CSO.kPrintToConsole: True, CSO.kPrintFileName: "print.log", diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 6bd294a2b245..dafc63c885fd 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -314,6 +314,9 @@ drake_cc_library( deps = [ ":solver_id", ], + implementation_deps = [ + "//common:overloaded", + ], ) drake_cc_library( diff --git a/solvers/solver_options.cc b/solvers/solver_options.cc index 0fef2ae7a9c0..d293cb1aa02f 100644 --- a/solvers/solver_options.cc +++ b/solvers/solver_options.cc @@ -7,6 +7,7 @@ #include #include "drake/common/never_destroyed.h" +#include "drake/common/overloaded.h" namespace drake { namespace solvers { @@ -20,22 +21,22 @@ using MapMap = std::unordered_map>; using CommonMap = std::unordered_map; -void SolverOptions::SetOption(const SolverId& solver_id, - const std::string& solver_option, - double option_value) { - solver_options_double_[solver_id][solver_option] = option_value; -} - -void SolverOptions::SetOption(const SolverId& solver_id, - const std::string& solver_option, - int option_value) { - solver_options_int_[solver_id][solver_option] = option_value; -} - -void SolverOptions::SetOption(const SolverId& solver_id, - const std::string& solver_option, - const std::string& option_value) { - solver_options_str_[solver_id][solver_option] = option_value; +void SolverOptions::SetOption(const SolverId& solver_id, std::string key, + OptionValue value) { + std::visit( + overloaded{ + [&](double unboxed_value) { + solver_options_double_[solver_id][std::move(key)] = unboxed_value; + }, + [&](int unboxed_value) { + solver_options_int_[solver_id][std::move(key)] = unboxed_value; + }, + [&](std::string&& unboxed_value) { + solver_options_str_[solver_id][std::move(key)] = + std::move(unboxed_value); + }, + }, + std::move(value)); } void SolverOptions::SetOption(CommonSolverOption key, OptionValue value) { diff --git a/solvers/solver_options.h b/solvers/solver_options.h index d6ad4a7beaae..22e41349d6c1 100644 --- a/solvers/solver_options.h +++ b/solvers/solver_options.h @@ -74,25 +74,14 @@ class SolverOptions { retrieve the variant's value in a future-proof way. */ using OptionValue = std::variant; - /** Sets a double-valued solver option for a specific solver. - @pydrake_mkdoc_identifier{double_option} */ - void SetOption(const SolverId& solver_id, const std::string& solver_option, - double option_value); - - /** Sets an integer-valued solver option for a specific solver. - @pydrake_mkdoc_identifier{int_option} */ - void SetOption(const SolverId& solver_id, const std::string& solver_option, - int option_value); - - /** Sets a string-valued solver option for a specific solver. - @pydrake_mkdoc_identifier{str_option} */ - void SetOption(const SolverId& solver_id, const std::string& solver_option, - const std::string& option_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(const SolverId& solver_id, std::string 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. - @pydrake_mkdoc_identifier{common_option} */ + option, the option is ignored. */ void SetOption(CommonSolverOption key, OptionValue value); const std::unordered_map& GetOptionsDouble(