Skip to content

Commit

Permalink
Pybind add constraint (#12371)
Browse files Browse the repository at this point in the history
Add python binding for MathematicalProgram::AddConstraint(constraint, vars)
  • Loading branch information
hongkai-dai committed Nov 20, 2019
1 parent 6dd04af commit a388cbb
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 2 deletions.
14 changes: 14 additions & 0 deletions bindings/pydrake/solvers/mathematicalprogram_py.cc
Expand Up @@ -512,6 +512,13 @@ top-level documentation for :py:mod:`pydrake.math`.
static_cast<Binding<Constraint> (MathematicalProgram::*)(
const Formula&)>(&MathematicalProgram::AddConstraint),
doc.MathematicalProgram.AddConstraint.doc_1args_f)
.def("AddConstraint",
static_cast<Binding<Constraint> (MathematicalProgram::*)(
std::shared_ptr<Constraint>,
const Eigen::Ref<const VectorXDecisionVariable>& vars)>(
&MathematicalProgram::AddConstraint),
py::arg("constraint"), py::arg("vars"),
doc.MathematicalProgram.AddConstraint.doc_2args_con_vars)
.def("AddLinearConstraint",
static_cast<Binding<LinearConstraint> (MathematicalProgram::*)(
const Eigen::Ref<const Eigen::MatrixXd>&,
Expand Down Expand Up @@ -977,6 +984,13 @@ top-level documentation for :py:mod:`pydrake.math`.

py::class_<LinearConstraint, Constraint, std::shared_ptr<LinearConstraint>>(
m, "LinearConstraint", doc.LinearConstraint.doc)
.def(py::init([](const Eigen::MatrixXd& A, const Eigen::VectorXd& lb,
const Eigen::VectorXd& ub) {
return std::unique_ptr<LinearConstraint>(
new LinearConstraint(A, lb, ub));
}),
py::arg("A"), py::arg("lb"), py::arg("ub"),
doc.LinearConstraint.ctor.doc)
.def("A", &LinearConstraint::A, doc.LinearConstraint.A.doc)
.def("UpdateCoefficients",
[](LinearConstraint& self, const Eigen::MatrixXd& new_A,
Expand Down
5 changes: 5 additions & 0 deletions bindings/pydrake/solvers/test/mathematicalprogram_test.py
Expand Up @@ -2,6 +2,7 @@
from pydrake.solvers.gurobi import GurobiSolver
from pydrake.solvers.snopt import SnoptSolver
from pydrake.solvers.mathematicalprogram import (
LinearConstraint,
MathematicalProgramResult,
SolverOptions,
SolverType,
Expand All @@ -22,6 +23,7 @@
from pydrake.math import ge
import pydrake.symbolic as sym


SNOPT_NO_GUROBI = SnoptSolver().available() and not GurobiSolver().available()


Expand Down Expand Up @@ -118,6 +120,9 @@ def test_mixed_integer_optimization(self):
a = np.array([1.0, 2.0, 3.0])
prog.AddLinearConstraint(a.dot(x) <= 4)
prog.AddLinearConstraint(x[0] + x[1], 1, np.inf)
prog.AddConstraint(
LinearConstraint(np.array([[1., 1.]]), np.array([1]),
np.array([np.inf])), [x[0], x[1]])
solver = GurobiSolver()
result = solver.Solve(prog, None, None)
self.assertTrue(result.is_success())
Expand Down
3 changes: 1 addition & 2 deletions solvers/mathematical_program.h
Expand Up @@ -1135,8 +1135,7 @@ class MathematicalProgram {
* only be used if a more specific type of constraint is not
* available, as it may require the use of a significantly more
* expensive solver.
*
* @exclude_from_pydrake_mkdoc{Not bound in pydrake.}
* @pydrake_mkdoc_identifier{2args_con_vars}
*/
template <typename C>
auto AddConstraint(std::shared_ptr<C> con,
Expand Down

0 comments on commit a388cbb

Please sign in to comment.