Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#12866 from RussTedrake/solve_defau…
Browse files Browse the repository at this point in the history
…lt_args

Add default std::nullopt arguments to SolverBase::Solve()
  • Loading branch information
sherm1 authored Mar 13, 2020
2 parents aebb159 + 586b731 commit 682dc48
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 5 deletions.
4 changes: 2 additions & 2 deletions bindings/pydrake/solvers/mathematicalprogram_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -254,8 +254,8 @@ top-level documentation for :py:mod:`pydrake.math`.
self.Solve(prog, initial_guess, solver_options, &result);
return result;
},
py::arg("prog"), py::arg("initial_guess"), py::arg("solver_options"),
doc.SolverBase.Solve.doc)
py::arg("prog"), py::arg("initial_guess") = std::nullopt,
py::arg("solver_options") = std::nullopt, doc.SolverBase.Solve.doc)
// TODO(m-chaturvedi) Add Pybind11 documentation.
.def("solver_type",
[](const SolverInterface& self) {
Expand Down
5 changes: 4 additions & 1 deletion bindings/pydrake/solvers/test/mathematicalprogram_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -668,7 +668,7 @@ def test_infeasible_constraints(self):
result = mp.Solve(prog)
infeasible = mp.GetInfeasibleConstraints(prog=prog, result=result,
tol=1e-4)
self.assertEquals(len(infeasible), 0)
self.assertEqual(len(infeasible), 0)

def test_add_indeterminates_and_decision_variables(self):
prog = mp.MathematicalProgram()
Expand Down Expand Up @@ -714,3 +714,6 @@ def test_dummy_solver_interface(self):
self.assertTrue("Dummy solver cannot solve" in str(context.exception))
self.assertIsInstance(result, mp.MathematicalProgramResult)
self.assertTrue(solver.AreProgramAttributesSatisfied(prog))
with self.assertRaises(Exception) as context:
result2 = solver.Solve(prog)
self.assertIsInstance(result2, mp.MathematicalProgramResult)
4 changes: 2 additions & 2 deletions solvers/solver_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ class SolverBase : public SolverInterface {
/// return value instead of an output argument.
MathematicalProgramResult Solve(
const MathematicalProgram& prog,
const std::optional<Eigen::VectorXd>& initial_guess,
const std::optional<SolverOptions>& solver_options) const;
const std::optional<Eigen::VectorXd>& initial_guess = std::nullopt,
const std::optional<SolverOptions>& solver_options = std::nullopt) const;

// Implement the SolverInterface methods.
void Solve(const MathematicalProgram&, const std::optional<Eigen::VectorXd>&,
Expand Down
4 changes: 4 additions & 0 deletions solvers/test/solver_base_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,10 @@ GTEST_TEST(SolverBaseTest, SolveAndReturn) {
const MathematicalProgramResult result = dut.Solve(prog, {}, {});
EXPECT_EQ(result.get_solver_id(), StubSolverBase::id());
EXPECT_TRUE(result.is_success());
// Confirm that default arguments work, too.
const MathematicalProgramResult result2 = dut.Solve(prog);
EXPECT_TRUE(result2.is_success());

// We don't bother checking additional result details here, because we know
// that the solve-and-return method is implemented as a thin shim atop the
// solve-as-output-argument method.
Expand Down

0 comments on commit 682dc48

Please sign in to comment.