Skip to content

Commit

Permalink
Add bindings for CsdpSolver (RobotLocomotion#13544)
Browse files Browse the repository at this point in the history
  • Loading branch information
mpetersen94 authored Jun 12, 2020
1 parent 36de86c commit 93ef69e
Show file tree
Hide file tree
Showing 12 changed files with 140 additions and 28 deletions.
55 changes: 34 additions & 21 deletions bindings/pydrake/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,20 @@ drake_cc_library(
visibility = ["//visibility:public"],
)

drake_pybind_library(
name = "csdp_py",
cc_deps = [
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:value_pybind",
],
cc_srcs = ["csdp_py.cc"],
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
"//bindings/pydrake/common:value_py",
],
)

drake_pybind_library(
name = "gurobi_py",
cc_deps = [
Expand All @@ -111,9 +125,7 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

Expand All @@ -127,9 +139,7 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

Expand All @@ -143,9 +153,7 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

Expand All @@ -160,9 +168,7 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

Expand All @@ -176,9 +182,7 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

Expand All @@ -192,9 +196,7 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

Expand All @@ -220,14 +222,13 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":mathematicalprogram_py",
# TODO(jwnimmer-tri) Only for AbstractValue; we should switch this to
# depend on on pydrake/common once the Value bindings have moved there.
"//bindings/pydrake/systems:framework_py",
"//bindings/pydrake/common:value_py",
],
)

PY_LIBRARIES_WITH_INSTALL = [
":branch_and_bound_py",
":csdp_py",
":gurobi_py",
":ipopt_py",
":mathematicalprogram_py",
Expand Down Expand Up @@ -264,6 +265,18 @@ install(
deps = get_drake_py_installs(PY_LIBRARIES_WITH_INSTALL),
)

drake_py_unittest(
name = "csdp_solver_test",
args = select({
"//tools:no_csdp": ["TestCsdptSolver.unavailable"],
"//conditions:default": [],
}),
deps = [
":csdp_py",
"//bindings/pydrake/common/test_utilities",
],
)

drake_py_unittest(
name = "gurobi_solver_test",
tags = gurobi_test_tags(),
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/solvers/all.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
from .mathematicalprogram import * # noqa
# TODO(eric.cousineau): Merge these into `mathematicalprogram`.
from .branch_and_bound import * # noqa
from .csdp import * # noqa
from .gurobi import * # noqa
from .ipopt import * # noqa
from .mixed_integer_optimization_util import * # noqa
Expand Down
41 changes: 41 additions & 0 deletions bindings/pydrake/solvers/csdp_py.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
#include "pybind11/eigen.h"
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/common/value_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/solvers/csdp_solver.h"

namespace drake {
namespace pydrake {

PYBIND11_MODULE(csdp, m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::solvers;
constexpr auto& doc = pydrake_doc.drake.solvers;

m.doc() = "Csdp solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");

py::class_<CsdpSolver, SolverInterface>(m, "CsdpSolver", doc.CsdpSolver.doc)
.def(py::init<>(), doc.CsdpSolver.ctor.doc);

py::class_<CsdpSolverDetails>(
m, "CsdpSolverDetails", doc.CsdpSolverDetails.doc)
.def_readonly("return_code", &CsdpSolverDetails::return_code,
doc.CsdpSolverDetails.return_code.doc)
.def_readonly("primal_objective", &CsdpSolverDetails::primal_objective,
doc.CsdpSolverDetails.primal_objective.doc)
.def_readonly("dual_objective", &CsdpSolverDetails::dual_objective,
doc.CsdpSolverDetails.dual_objective.doc)
.def_readonly(
"y_val", &CsdpSolverDetails::y_val, doc.CsdpSolverDetails.y_val.doc)
.def_readonly(
"Z_val", &CsdpSolverDetails::Z_val, doc.CsdpSolverDetails.Z_val.doc);
AddValueInstantiation<CsdpSolverDetails>(m);
}

} // namespace pydrake
} // namespace drake
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/gurobi_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@ PYBIND11_MODULE(gurobi, m) {

m.doc() = "Gurobi solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<GurobiSolver, SolverInterface> cls(
m, "GurobiSolver", doc.GurobiSolver.doc);
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/ipopt_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ PYBIND11_MODULE(ipopt, m) {

m.doc() = "Ipopt solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<IpoptSolver, SolverInterface>(
m, "IpoptSolver", doc.IpoptSolver.doc)
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/solvers/mathematicalprogram_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -344,6 +344,7 @@ top-level documentation for :py:mod:`pydrake.math`.
.def("name", &SolverId::name, doc.SolverId.name.doc);

py::enum_<SolverType>(m, "SolverType", doc.SolverType.doc)
.value("kCsdp", SolverType::kCsdp, doc.SolverType.kCsdp.doc)
.value("kDReal", SolverType::kDReal, doc.SolverType.kDReal.doc)
.value("kEqualityConstrainedQP", SolverType::kEqualityConstrainedQP,
doc.SolverType.kEqualityConstrainedQP.doc)
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/mosek_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@ PYBIND11_MODULE(mosek, m) {

m.doc() = "Mosek solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<MosekSolver, SolverInterface> cls(
m, "MosekSolver", doc.MosekSolver.doc);
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/nlopt_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ PYBIND11_MODULE(nlopt, m) {

m.doc() = "NLopt solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<NloptSolver, SolverInterface>(
m, "NloptSolver", doc.NloptSolver.doc)
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/osqp_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ PYBIND11_MODULE(osqp, m) {

m.doc() = "OSQP solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<OsqpSolver, SolverInterface>(m, "OsqpSolver", doc.OsqpSolver.doc)
.def(py::init<>(), doc.OsqpSolver.ctor.doc);
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/scs_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ PYBIND11_MODULE(scs, m) {

m.doc() = "SCS solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<ScsSolver, SolverInterface>(m, "ScsSolver", doc.ScsSolver.doc)
.def(py::init<>(), doc.ScsSolver.ctor.doc);
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/snopt_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ PYBIND11_MODULE(snopt, m) {

m.doc() = "SNOPT solver bindings for MathematicalProgram";

py::module::import("pydrake.common.value");
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.systems.framework");

py::class_<SnoptSolver, SolverInterface>(
m, "SnoptSolver", doc.SnoptSolver.doc)
Expand Down
56 changes: 56 additions & 0 deletions bindings/pydrake/solvers/test/csdp_solver_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
import unittest
import warnings

import numpy as np

from pydrake.solvers import mathematicalprogram as mp
from pydrake.solvers.csdp import CsdpSolver


class TestCsdpSolver(unittest.TestCase):
def _make_prog(self):
prog = mp.MathematicalProgram()
x1 = prog.NewSymmetricContinuousVariables(2, "x1")
x2 = prog.NewSymmetricContinuousVariables(3, "x2")
y = prog.NewContinuousVariables(2, "y")
prog.AddPositiveSemidefiniteConstraint(x1)
prog.AddPositiveSemidefiniteConstraint(x2)
prog.AddLinearConstraint(y[0] >= 0)
prog.AddLinearConstraint(y[1] >= 0)
prog.AddLinearEqualityConstraint(3*x1[0, 0] + 2*x1[0, 1] + 3*x1[1, 1]
+ y[0] == 1)
prog.AddLinearEqualityConstraint(3*x2[0, 0] + 4*x2[1, 1] + 2*x2[0, 2]
+ 5*x2[2, 2] + y[1] == 2)
prog.AddLinearCost(-(2*x1[0, 0] + 2*x1[0, 1] + 2*x1[1, 1] + 3*x2[0, 0]
+ 2*x2[1, 1] + 2*x2[0, 2] + 3*x2[2, 2]))
x1_expected = 0.125 * np.ones((2, 2))
return prog, x1, x1_expected

def test_csdp_solver(self):
prog, x1, x1_expected = self._make_prog()
solver = CsdpSolver()
self.assertTrue(solver.available())
self.assertEqual(solver.solver_id().name(), "CSDP")
self.assertEqual(solver.SolverName(), "CSDP")
self.assertEqual(solver.solver_type(), mp.SolverType.kCsdp)
result = solver.Solve(prog, None, None)
self.assertTrue(result.is_success())
self.assertTrue(np.allclose(result.GetSolution(x1), x1_expected))
self.assertEqual(result.get_solver_details().return_code, 0)
np.testing.assert_allclose(
result.get_solver_details().primal_objective, 2.75)
np.testing.assert_allclose(
result.get_solver_details().dual_objective, 2.75)
np.testing.assert_allclose(
result.get_solver_details().y_val, np.array([0.75, 1.]))
z_expected = np.zeros((7, 7))
z_expected[0, :2] = [0.25, -0.25]
z_expected[1, :2] = [-0.25, 0.25]
z_expected[3:, 3:] = np.diag([2., 2., 0.75, 1.])
np.testing.assert_allclose(
result.get_solver_details().Z_val.toarray(), z_expected, atol=1e-8)

def unavailable(self):
"""Per the BUILD file, this test is only run when CSDP is disabled."""
solver = CsdpSolver()
self.assertFalse(solver.available())

0 comments on commit 93ef69e

Please sign in to comment.