Skip to content

Commit

Permalink
CsdpSolver accepts RemoveFreeVariableMethod via SolverOptions (RobotL…
Browse files Browse the repository at this point in the history
…ocomotion#17275)

Also deprecate the constructor with RemoveFreeVariableMethod argument.
  • Loading branch information
hongkai-dai authored Jun 6, 2022
1 parent 925e382 commit 789e434
Show file tree
Hide file tree
Showing 19 changed files with 274 additions and 102 deletions.
1 change: 1 addition & 0 deletions bindings/pydrake/solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ drake_pybind_library(
name = "csdp_py",
cc_deps = [
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:value_pybind",
],
cc_srcs = ["csdp_py.cc"],
Expand Down
16 changes: 12 additions & 4 deletions bindings/pydrake/solvers/csdp_py.cc
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
#include "pybind11/eigen.h"
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/common/deprecation_pybind.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"
#include "drake/solvers/sdpa_free_format.h"

namespace drake {
namespace pydrake {
Expand All @@ -20,12 +22,18 @@ PYBIND11_MODULE(csdp, m) {
py::module::import("pydrake.solvers.mathematicalprogram");
py::module::import("pydrake.solvers.sdpa_free_format");

py::class_<CsdpSolver, SolverInterface>(m, "CsdpSolver", doc.CsdpSolver.doc)
.def(py::init<RemoveFreeVariableMethod>(),
py::arg("method") = RemoveFreeVariableMethod::kNullspace,
doc.CsdpSolver.ctor.doc)
py::class_<CsdpSolver, SolverInterface> csdp_cls(
m, "CsdpSolver", doc.CsdpSolver.doc);
csdp_cls.def(py::init<>(), doc.CsdpSolver.ctor.doc)
.def_static("id", &CsdpSolver::id, doc.CsdpSolver.id.doc);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
csdp_cls.def(py_init_deprecated<CsdpSolver, RemoveFreeVariableMethod>(
doc.CsdpSolver.ctor.doc_deprecated),
py::arg("method"), doc.CsdpSolver.ctor.doc_deprecated);
#pragma GCC diagnostic pop

py::class_<CsdpSolverDetails>(
m, "CsdpSolverDetails", doc.CsdpSolverDetails.doc)
.def_readonly("return_code", &CsdpSolverDetails::return_code,
Expand Down
21 changes: 17 additions & 4 deletions bindings/pydrake/solvers/test/csdp_solver_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
from pydrake.solvers import mathematicalprogram as mp
from pydrake.solvers.csdp import CsdpSolver
import pydrake.solvers.sdpa_free_format as sdpa_free_format
from pydrake.common.test_utilities.deprecation import catch_drake_warnings


class TestCsdpSolver(unittest.TestCase):
Expand Down Expand Up @@ -35,7 +36,12 @@ def test_csdp_solver(self):
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)
solver_options = mp.SolverOptions()
solver_options.SetOption(
solver.id(),
"drake::RemoveFreeVariableMethod",
sdpa_free_format.RemoveFreeVariableMethod.kNullspace)
result = solver.Solve(prog, None, solver_options)
self.assertTrue(result.is_success())
self.assertTrue(np.allclose(result.GetSolution(x1), x1_expected))
self.assertEqual(result.get_solver_details().return_code, 0)
Expand All @@ -53,10 +59,17 @@ def test_csdp_solver(self):
result.get_solver_details().Z_val.todense(), z_expected, atol=1e-8)

# Test removing free variables with a non-default method.
solver = CsdpSolver(
method=sdpa_free_format.RemoveFreeVariableMethod.kLorentzConeSlack)
result = solver.Solve(prog, None, None)
solver = CsdpSolver()
solver_options = mp.SolverOptions()
solver_options.SetOption(
solver.id(), "drake::RemoveFreeVariableMethod",
sdpa_free_format.RemoveFreeVariableMethod.kLorentzConeSlack)
result = solver.Solve(prog, None, solver_options)
self.assertTrue(result.is_success())
with catch_drake_warnings(expected_count=1):
CsdpSolver(
method=sdpa_free_format.RemoveFreeVariableMethod.
kLorentzConeSlack)

def unavailable(self):
"""Per the BUILD file, this test is only run when CSDP is disabled."""
Expand Down
15 changes: 14 additions & 1 deletion solvers/csdp_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "drake/common/scope_exit.h"
#include "drake/common/text_logging.h"
#include "drake/solvers/csdp_solver_internal.h"
#include "drake/solvers/sdpa_free_format.h"

// Note that in the below, the first argument to csdp::cpp_easy_sdp is a params
// filename, but that feature is a Drake-specific patch added to the CSDP
Expand Down Expand Up @@ -471,7 +472,19 @@ void CsdpSolver::DoSolve(const MathematicalProgram& prog,
internal::SolveProgramWithNoFreeVariables(
prog, sdpa_free_format, csdp_params_pathname, result);
} else {
switch (method_) {
const auto int_options = merged_options.GetOptionsInt(CsdpSolver::id());
const auto it_method = int_options.find("drake::RemoveFreeVariableMethod");
RemoveFreeVariableMethod method = method_;
if (it_method != int_options.end()) {
if (it_method->second >= 1 && it_method->second <= 3) {
method = static_cast<RemoveFreeVariableMethod>(it_method->second);
} else {
throw std::runtime_error(
"CsdpSolver::sol(), unknown value for "
"drake::RemoveFreeVariableMethod");
}
}
switch (method) {
case RemoveFreeVariableMethod::kNullspace: {
internal::SolveProgramThroughNullspaceApproach(
prog, sdpa_free_format, csdp_params_pathname, result);
Expand Down
34 changes: 32 additions & 2 deletions solvers/csdp_solver.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/solvers/sdpa_free_format.h"
#include "drake/solvers/solver_base.h"

Expand Down Expand Up @@ -46,12 +47,39 @@ struct CsdpSolverDetails {
Eigen::SparseMatrix<double> Z_val;
};

/**
* Wrap CSDP solver such that it can solve a
* drake::solvers::MathematicalProgram.
* @note CSDP doesn't accept free variables, while
* drake::solvers::MathematicalProgram does. In order to convert
* MathematicalProgram into CSDP format, we provide several approaches to remove
* free variables. You can set the approach through
* @code{cc}
* SolverOptions solver_options;
* solver_options.SetOption(CsdpSolver::id(),
* "drake::RemoveFreeVariableMethod",
* static_cast<int>(RemoveFreeVariableMethod::kNullspace));
* CsdpSolver solver;
* auto result = solver.Solve(prog, std::nullopt, solver_options);
* @endcode
* For more details, check out RemoveFreeVariableMethod.
*/
class CsdpSolver final : public SolverBase {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CsdpSolver)

explicit CsdpSolver(
RemoveFreeVariableMethod method = RemoveFreeVariableMethod::kNullspace);
/**
* Constructs CsdpSolver with a specified method to remove free variables.
*/
DRAKE_DEPRECATED(
"2022-09-01",
"Use the CsdpSolver() constructor without an input argument, and set the "
"method through SetOption(CsdpSolver::id(), "
"\"drake::RemoveFreeVariableMethod\", METHOD)")
explicit CsdpSolver(RemoveFreeVariableMethod method);

/** Default constructor */
CsdpSolver();

~CsdpSolver() final;

Expand All @@ -72,6 +100,8 @@ class CsdpSolver final : public SolverBase {
void DoSolve(const MathematicalProgram&, const Eigen::VectorXd&,
const SolverOptions&, MathematicalProgramResult*) const final;

// TODO(hongkai.dai): remove this field on 2022-09-01 when we deprecate the
// constructor with input argument `method`.
RemoveFreeVariableMethod method_;
};
} // namespace solvers
Expand Down
4 changes: 4 additions & 0 deletions solvers/csdp_solver_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@ CsdpSolver::CsdpSolver(RemoveFreeVariableMethod method)
: SolverBase(&id, &is_available, &is_enabled, &ProgramAttributesSatisfied),
method_{method} {}

CsdpSolver::CsdpSolver()
: SolverBase(&id, &is_available, &is_enabled, &ProgramAttributesSatisfied),
method_{RemoveFreeVariableMethod::kNullspace} {}

CsdpSolver::~CsdpSolver() = default;

SolverId CsdpSolver::id() {
Expand Down
12 changes: 6 additions & 6 deletions solvers/sdpa_free_format.h
Original file line number Diff line number Diff line change
Expand Up @@ -459,12 +459,12 @@ class SdpaFreeFormat {
*
*/
enum class RemoveFreeVariableMethod {
kTwoSlackVariables, ///< Approach 1, replace a free variable s as
///< s = y⁺ - y⁻, y⁺ ≥ 0, y⁻ ≥ 0.
kNullspace, ///< Approach 2, reformulate the dual problem by considering
///< the nullspace of the linear constraint in the dual.
kLorentzConeSlack, ///< Approach 3, add a slack variable t with the lorentz
///< cone constraint t ≥ sqrt(sᵀs).
kTwoSlackVariables = 1, ///< Approach 1, replace a free variable s as
///< s = y⁺ - y⁻, y⁺ ≥ 0, y⁻ ≥ 0.
kNullspace = 2, ///< Approach 2, reformulate the dual problem by considering
///< the nullspace of the linear constraint in the dual.
kLorentzConeSlack = 3, ///< Approach 3, add a slack variable t with the
///< lorentz cone constraint t ≥ sqrt(sᵀs).
};

/**
Expand Down
Loading

0 comments on commit 789e434

Please sign in to comment.