Skip to content

Commit

Permalink
[py solvers] Split options bindings into their own file (RobotLocomot…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored and RussTedrake committed Dec 15, 2024
1 parent fbb71d2 commit 5ba7078
Show file tree
Hide file tree
Showing 5 changed files with 89 additions and 66 deletions.
1 change: 1 addition & 0 deletions bindings/pydrake/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ drake_pybind_library(
"solvers_py_mobylcp.cc",
"solvers_py_mosek.cc",
"solvers_py_nlopt.cc",
"solvers_py_options.cc",
"solvers_py_osqp.cc",
"solvers_py_scs.cc",
"solvers_py_sdpa_free_format.cc",
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/solvers/solvers_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ top-level documentation for :py:mod:`pydrake.math`.
// The order of these calls matters. Some modules rely on prior definitions.
internal::DefineSolversEvaluators(m);
internal::DefineProgramAttribute(m);
internal::DefineSolversOptions(m);
internal::DefineSolversMathematicalProgram(m);
internal::DefineSolversAugmentedLagrangian(m);
internal::DefineSolversBranchAndBound(m);
Expand Down
3 changes: 3 additions & 0 deletions bindings/pydrake/solvers/solvers_py.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,9 @@ void DefineSolversMosek(py::module m);
/* Defines the NLOPT bindings. See solvers_py_nlopt.cc. */
void DefineSolversNlopt(py::module m);

/* Defines the SolverOptions bindings. See solvers_py_options.cc. */
void DefineSolversOptions(py::module m);

/* Defines the OSQP bindings. See solvers_py_osqp.cc. */
void DefineSolversOsqp(py::module m);

Expand Down
66 changes: 0 additions & 66 deletions bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc
Original file line number Diff line number Diff line change
Expand Up @@ -375,71 +375,6 @@ void BindSolverIdAndType(py::module m) {
doc.SolverType.kUnrevisedLemke.doc);
}

void BindSolverOptions(py::module m) {
constexpr auto& doc = pydrake_doc.drake.solvers;

py::enum_<CommonSolverOption>(
m, "CommonSolverOption", doc.CommonSolverOption.doc)
.value("kPrintFileName", CommonSolverOption::kPrintFileName,
doc.CommonSolverOption.kPrintFileName.doc)
.value("kPrintToConsole", CommonSolverOption::kPrintToConsole,
doc.CommonSolverOption.kPrintToConsole.doc)
.value("kStandaloneReproductionFileName",
CommonSolverOption::kStandaloneReproductionFileName,
doc.CommonSolverOption.kStandaloneReproductionFileName.doc);

// TODO(jwnimmer-tri) Bind the accessors for SolverOptions.
py::class_<SolverOptions>(m, "SolverOptions", doc.SolverOptions.doc)
.def(py::init<>(), doc.SolverOptions.ctor.doc)
.def("SetOption",
py::overload_cast<const SolverId&, const std::string&, double>(
&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<const SolverId&, const std::string&, int>(
&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<const SolverId&, const std::string&,
const std::string&>(&SolverOptions::SetOption),
py::arg("solver_id"), py::arg("solver_option"),
py::arg("option_value"), doc.SolverOptions.SetOption.doc_str_option)
.def("SetOption",
py::overload_cast<CommonSolverOption, SolverOptions::OptionValue>(
&SolverOptions::SetOption),
py::arg("key"), py::arg("value"),
doc.SolverOptions.SetOption.doc_common_option)
.def(
"GetOptions",
[](const SolverOptions& solver_options, SolverId solver_id) {
py::dict out;
py::object update = out.attr("update");
update(solver_options.GetOptionsDouble(solver_id));
update(solver_options.GetOptionsInt(solver_id));
update(solver_options.GetOptionsStr(solver_id));
return out;
},
py::arg("solver_id"), doc.SolverOptions.GetOptionsDouble.doc)
.def("common_solver_options", &SolverOptions::common_solver_options,
doc.SolverOptions.common_solver_options.doc)
.def("get_print_file_name", &SolverOptions::get_print_file_name,
doc.SolverOptions.get_print_file_name.doc)
.def("get_print_to_console", &SolverOptions::get_print_to_console,
doc.SolverOptions.get_print_to_console.doc)
.def("get_standalone_reproduction_file_name",
&SolverOptions::get_standalone_reproduction_file_name,
doc.SolverOptions.get_standalone_reproduction_file_name.doc)
.def("__repr__", [](const SolverOptions&) -> std::string {
// This is a minimal implementation that serves to avoid displaying
// memory addresses in pydrake docs and help strings. In the future,
// we should enhance this to provide more details.
return "<SolverOptions>";
});
}

void BindMathematicalProgramResult(py::module m) {
constexpr auto& doc = pydrake_doc.drake.solvers;
py::class_<MathematicalProgramResult>(
Expand Down Expand Up @@ -1763,7 +1698,6 @@ void DefineSolversMathematicalProgram(py::module m) {
// This list must remain in topological dependency order.
BindPyFunctionConstraint(m);
BindSolverIdAndType(m);
BindSolverOptions(m);
BindMathematicalProgram(m);
BindSolutionResult(m);
BindMathematicalProgramResult(m);
Expand Down
84 changes: 84 additions & 0 deletions bindings/pydrake/solvers/solvers_py_options.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/bindings/pydrake/solvers/solvers_py.h"
#include "drake/solvers/common_solver_option.h"
#include "drake/solvers/solver_options.h"

namespace drake {
namespace pydrake {
namespace internal {

void DefineSolversOptions(py::module m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::solvers;
constexpr auto& doc = pydrake_doc.drake.solvers;

{
py::enum_<CommonSolverOption>(
m, "CommonSolverOption", doc.CommonSolverOption.doc)
.value("kPrintFileName", CommonSolverOption::kPrintFileName,
doc.CommonSolverOption.kPrintFileName.doc)
.value("kPrintToConsole", CommonSolverOption::kPrintToConsole,
doc.CommonSolverOption.kPrintToConsole.doc)
.value("kStandaloneReproductionFileName",
CommonSolverOption::kStandaloneReproductionFileName,
doc.CommonSolverOption.kStandaloneReproductionFileName.doc);
}

{
// TODO(jwnimmer-tri) Bind the accessors for SolverOptions.
py::class_<SolverOptions>(m, "SolverOptions", doc.SolverOptions.doc)
.def(py::init<>(), doc.SolverOptions.ctor.doc)
.def("SetOption",
py::overload_cast<const SolverId&, const std::string&, double>(
&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<const SolverId&, const std::string&, int>(
&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<const SolverId&, const std::string&,
const std::string&>(&SolverOptions::SetOption),
py::arg("solver_id"), py::arg("solver_option"),
py::arg("option_value"), doc.SolverOptions.SetOption.doc_str_option)
.def("SetOption",
py::overload_cast<CommonSolverOption, SolverOptions::OptionValue>(
&SolverOptions::SetOption),
py::arg("key"), py::arg("value"),
doc.SolverOptions.SetOption.doc_common_option)
.def(
"GetOptions",
[](const SolverOptions& solver_options, SolverId solver_id) {
py::dict out;
py::object update = out.attr("update");
update(solver_options.GetOptionsDouble(solver_id));
update(solver_options.GetOptionsInt(solver_id));
update(solver_options.GetOptionsStr(solver_id));
return out;
},
py::arg("solver_id"), doc.SolverOptions.GetOptionsDouble.doc)
.def("common_solver_options", &SolverOptions::common_solver_options,
doc.SolverOptions.common_solver_options.doc)
.def("get_print_file_name", &SolverOptions::get_print_file_name,
doc.SolverOptions.get_print_file_name.doc)
.def("get_print_to_console", &SolverOptions::get_print_to_console,
doc.SolverOptions.get_print_to_console.doc)
.def("get_standalone_reproduction_file_name",
&SolverOptions::get_standalone_reproduction_file_name,
doc.SolverOptions.get_standalone_reproduction_file_name.doc)
.def("__repr__", [](const SolverOptions&) -> std::string {
// This is a minimal implementation that serves to avoid displaying
// memory addresses in pydrake docs and help strings. In the future,
// we should enhance this to provide more details.
return "<SolverOptions>";
});
}
}

} // namespace internal
} // namespace pydrake
} // namespace drake

0 comments on commit 5ba7078

Please sign in to comment.