Skip to content

Commit

Permalink
Remove prog.solve() in solvers folder. (#10405)
Browse files Browse the repository at this point in the history
Remove prog.solve() in solvers folder, ass overloaded Solve() method as syntax sugars.
  • Loading branch information
hongkai-dai authored Jan 15, 2019
1 parent 780f815 commit b9e9c4f
Show file tree
Hide file tree
Showing 23 changed files with 177 additions and 122 deletions.
10 changes: 10 additions & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -345,6 +345,7 @@ drake_cc_library(
hdrs = ["non_convex_optimization_util.h"],
deps = [
":mathematical_program",
":solve",
"//math:quadratic_form",
],
)
Expand Down Expand Up @@ -1005,6 +1006,7 @@ drake_cc_googletest(
tags = ["snopt"],
deps = [
":mathematical_program",
":solve",
],
)

Expand Down Expand Up @@ -1032,6 +1034,7 @@ drake_cc_googletest(
deps = [
":mathematical_program",
":mathematical_program_test_util",
":solve",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
],
Expand Down Expand Up @@ -1092,6 +1095,7 @@ drake_cc_googletest(
deps = [
":integer_optimization_util",
":mathematical_program",
":solve",
],
)

Expand All @@ -1117,6 +1121,7 @@ drake_cc_googletest(
],
deps = [
":mathematical_program",
":solve",
"//common/test_utilities:eigen_matrix_compare",
],
)
Expand Down Expand Up @@ -1145,6 +1150,7 @@ drake_cc_googletest(
":generic_trivial_cost",
":mathematical_program",
":mathematical_program_test_util",
":solve",
"//common:symbolic",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:is_dynamic_castable",
Expand Down Expand Up @@ -1311,6 +1317,7 @@ drake_cc_googletest(
":gurobi_solver",
":mathematical_program",
":rotation_constraint",
":solve",
"//common/test_utilities:eigen_matrix_compare",
"//math:geometric_transform",
],
Expand Down Expand Up @@ -1466,6 +1473,7 @@ drake_cc_googletest(
deps = [
":mathematical_program",
":mixed_integer_rotation_constraint",
":solve",
"//common/test_utilities:eigen_matrix_compare",
"//math:geometric_transform",
],
Expand All @@ -1475,6 +1483,7 @@ drake_cc_googletest(
name = "diagonally_dominant_matrix_test",
deps = [
":mathematical_program",
":solve",
"//common/test_utilities:eigen_matrix_compare",
],
)
Expand All @@ -1484,6 +1493,7 @@ drake_cc_googletest(
tags = gurobi_test_tags() + mosek_test_tags(),
deps = [
":mathematical_program",
":solve",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:symbolic_test_util",
],
Expand Down
4 changes: 2 additions & 2 deletions solvers/constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -738,10 +738,10 @@ class PositiveSemidefiniteConstraint : public Constraint {
* /////////////////////////////////////////////////////////////
*
* // Now solve the program.
* prog.Solve();
* auto result = Solve(prog);
*
* // Retrieve the solution of matrix S.
* auto S_value = GetSolution(S);
* auto S_value = GetSolution(S, result);
*
* // Compute the eigen values of the solution, to see if they are
* // all non-negative.
Expand Down
9 changes: 5 additions & 4 deletions solvers/non_convex_optimization_util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include "drake/math/quadratic_form.h"
#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/solve.h"

namespace drake {
namespace solvers {
Expand Down Expand Up @@ -37,16 +38,16 @@ std::pair<Eigen::MatrixXd, Eigen::MatrixXd> DecomposeNonConvexQuadraticForm(
prog.AddLinearConstraint(symbolic::Expression(s) >=
Q2.cast<symbolic::Expression>().trace());
prog.AddCost(s);
SolutionResult result = prog.Solve();
const MathematicalProgramResult result = Solve(prog);
// This problem should always be feasible, since we can choose Q1 to a large
// diagonal matrix, and Q2 will also have large diagonal entries. Both Q1 and
// Q2 are diagonally dominant, thus they are both positive definite.
// Due to positive definiteness, both trace(Q1) and trace(Q2) are
// non-negative, so min(max(trace(Q1), trace(Q2)) is lower bounded. Hence,
// this optimal cost is not un-bounded.
DRAKE_DEMAND(result == SolutionResult::kSolutionFound);
auto Q1_sol = prog.GetSolution(Q1);
auto Q2_sol = prog.GetSolution(Q2);
DRAKE_DEMAND(result.get_solution_result() == SolutionResult::kSolutionFound);
auto Q1_sol = prog.GetSolution(Q1, result);
auto Q2_sol = prog.GetSolution(Q2, result);
return std::make_pair(Q1_sol, Q2_sol);
}

Expand Down
11 changes: 11 additions & 0 deletions solvers/solve.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,5 +17,16 @@ MathematicalProgramResult Solve(const MathematicalProgram& prog,
solver->Solve(prog, initial_guess, solver_options, &result);
return result;
}

MathematicalProgramResult Solve(
const MathematicalProgram& prog,
const Eigen::Ref<const Eigen::VectorXd>& initial_guess) {
const Eigen::VectorXd initial_guess_xd = initial_guess;
return Solve(prog, initial_guess_xd, {});
}

MathematicalProgramResult Solve(const MathematicalProgram& prog) {
return Solve(prog, {}, {});
}
} // namespace solvers
} // namespace drake
9 changes: 9 additions & 0 deletions solvers/solve.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,5 +19,14 @@ namespace solvers {
MathematicalProgramResult Solve(const MathematicalProgram& prog,
const optional<Eigen::VectorXd>& initial_guess,
const optional<SolverOptions>& solver_options);

/**
* Solves an optimization program with a given initial guess.
*/
MathematicalProgramResult Solve(
const MathematicalProgram& prog,
const Eigen::Ref<const Eigen::VectorXd>& initial_guess);

MathematicalProgramResult Solve(const MathematicalProgram& prog);
} // namespace solvers
} // namespace drake
9 changes: 5 additions & 4 deletions solvers/test/complementary_problem_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/snopt_solver.h"
#include "drake/solvers/solve.h"

namespace drake {
namespace solvers {
Expand Down Expand Up @@ -82,10 +83,10 @@ GTEST_TEST(TestComplementaryProblem, flp2) {
prog.AddBoundingBoxConstraint(0, 10, x);
SnoptSolver snopt_solver;
if (snopt_solver.available()) {
auto result = prog.Solve();
EXPECT_EQ(result, SolutionResult::kSolutionFound);
const auto x_val = prog.GetSolution(x);
const auto y_val = prog.GetSolution(y);
MathematicalProgramResult result = Solve(prog);
EXPECT_EQ(result.get_solution_result(), SolutionResult::kSolutionFound);
const auto x_val = prog.GetSolution(x, result);
const auto y_val = prog.GetSolution(y, result);
// Choose 1e-6 as the precision, since that is the default minor feasibility
// tolerance of SNOPT.
double precision = 1E-6;
Expand Down
36 changes: 21 additions & 15 deletions solvers/test/diagonally_dominant_matrix_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/snopt_solver.h"
#include "drake/solvers/solve.h"

namespace drake {
namespace solvers {
Expand Down Expand Up @@ -45,22 +46,26 @@ GTEST_TEST(DiagonallyDominantMatrixConstraint, FeasibilityCheck) {

// [1 0.9;0.9 2] is diagonally dominant
set_X_value(Eigen::Vector3d(1, 0.9, 2));
EXPECT_EQ(prog.Solve(), SolutionResult::kSolutionFound);
MathematicalProgramResult result = Solve(prog);
EXPECT_EQ(result.get_solution_result(), SolutionResult::kSolutionFound);

// [1 -0.9; -0.9 2] is diagonally dominant
set_X_value(Eigen::Vector3d(1, -0.9, 2));
EXPECT_EQ(prog.Solve(), SolutionResult::kSolutionFound);
result = Solve(prog);
EXPECT_EQ(result.get_solution_result(), SolutionResult::kSolutionFound);

// [1 1.1; 1.1 2] is not diagonally dominant
set_X_value(Eigen::Vector3d(1, 1.1, 2));
auto result = prog.Solve();
EXPECT_TRUE(result == SolutionResult::kInfeasibleConstraints ||
result == SolutionResult::kInfeasible_Or_Unbounded);
result = Solve(prog);
EXPECT_TRUE(
result.get_solution_result() == SolutionResult::kInfeasibleConstraints ||
result.get_solution_result() == SolutionResult::kInfeasible_Or_Unbounded);
// [1 -1.1; -1.1 2] is not diagonally dominant
set_X_value(Eigen::Vector3d(1, -1.1, 2));
result = prog.Solve();
EXPECT_TRUE(result == SolutionResult::kInfeasibleConstraints ||
result == SolutionResult::kInfeasible_Or_Unbounded);
result = Solve(prog);
EXPECT_TRUE(
result.get_solution_result() == SolutionResult::kInfeasibleConstraints ||
result.get_solution_result() == SolutionResult::kInfeasible_Or_Unbounded);
}

GTEST_TEST(DiagonallyDominantMatrixConstraint, three_by_three_vertices) {
Expand Down Expand Up @@ -88,19 +93,20 @@ GTEST_TEST(DiagonallyDominantMatrixConstraint, three_by_three_vertices) {

auto solve_and_check = [&prog, &X](const Eigen::Vector3d& sol_expected,
double tol) {
const auto result = prog.Solve();
if (prog.GetSolverId() && prog.GetSolverId().value() != SnoptSolver::id()) {
const auto result = Solve(prog);
if (result.get_solver_id() != SnoptSolver::id()) {
// Do not check when we use SNOPT. It is known that our SnoptSolver
// wrapper doesn't solve this problem correctly, see
// https://github.com/RobotLocomotion/drake/pull/9382
// TODO(hongkai.dai): fix the problem in SnoptSolver wrapper and enable
// this test with Snopt.
EXPECT_EQ(result, SolutionResult::kSolutionFound);
EXPECT_TRUE(CompareMatrices(prog.GetSolution(VectorDecisionVariable<3>(
X(0, 1), X(0, 2), X(1, 2))),
sol_expected, tol));
EXPECT_EQ(result.get_solution_result(), SolutionResult::kSolutionFound);
EXPECT_TRUE(CompareMatrices(
prog.GetSolution(VectorDecisionVariable<3>(X(0, 1), X(0, 2), X(1, 2)),
result),
sol_expected, tol));
// The matrix should be positive semidefinite.
const Eigen::Matrix3d X_sol = prog.GetSolution(X);
const Eigen::Matrix3d X_sol = prog.GetSolution(X, result);
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigen_solver(X_sol);
EXPECT_TRUE((eigen_solver.eigenvalues().array() >= -tol).all());
}
Expand Down
45 changes: 24 additions & 21 deletions solvers/test/equality_constrained_qp_solver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/solve.h"
#include "drake/solvers/test/mathematical_program_test_util.h"

using Eigen::MatrixXd;
Expand All @@ -31,39 +32,39 @@ GTEST_TEST(testEqualityConstrainedQPSolver, testUnconstrainedQPDispatch) {
auto x = prog.NewContinuousVariables<2>();
prog.AddCost(pow(x(0) - 1, 2) + pow(x(1) - 1, 2));

prog.Solve();
MathematicalProgramResult result = Solve(prog);

VectorXd expected_answer(2);
expected_answer << 1.0, 1.0;
auto x_value = prog.GetSolution(x);
auto x_value = prog.GetSolution(x, result);
EXPECT_TRUE(CompareMatrices(expected_answer, x_value, 1e-10,
MatrixCompareType::absolute));
EXPECT_NEAR(0.0, prog.GetOptimalCost(), 1e-10);
EXPECT_NEAR(0.0, result.get_optimal_cost(), 1e-10);

// There are no inequality constraints, and only quadratic costs,
// so this should hold:
CheckSolver(prog, EqualityConstrainedQPSolver::id());
EXPECT_EQ(result.get_solver_id(), EqualityConstrainedQPSolver::id());

// Add one more variable and constrain a view into them.
auto y = prog.NewContinuousVariables<1>("y");

prog.AddCost(pow(x(1) - 3, 2) + pow(2 * y(0) - 4, 2));
prog.SetInitialGuessForAllVariables(Eigen::Vector3d::Zero());
prog.Solve();
result = Solve(prog);
expected_answer.resize(3);
expected_answer << 1.0, 2.0, 2.0;
VectorXd actual_answer(3);
x_value = prog.GetSolution(x);
const auto& y_value = prog.GetSolution(y);
x_value = prog.GetSolution(x, result);
const auto& y_value = prog.GetSolution(y, result);
actual_answer << x_value, y_value;
EXPECT_TRUE(CompareMatrices(expected_answer, actual_answer, 1e-10,
MatrixCompareType::absolute))
<< "\tExpected: " << expected_answer.transpose()
<< "\tActual: " << actual_answer.transpose();
EXPECT_NEAR(2.0, prog.GetOptimalCost(), 1e-10);
EXPECT_NEAR(2.0, result.get_optimal_cost(), 1e-10);

// Problem still has only quadratic costs, so solver should be the same.
CheckSolver(prog, EqualityConstrainedQPSolver::id());
EXPECT_EQ(result.get_solver_id(), EqualityConstrainedQPSolver::id());
}

// Test how an equality-constrained QP is dispatched
Expand All @@ -84,19 +85,19 @@ GTEST_TEST(testEqualityConstrainedQPSolver, testLinearlyConstrainedQPDispatch) {

prog.SetInitialGuessForAllVariables(Eigen::Vector2d::Zero());

prog.Solve();
MathematicalProgramResult result = Solve(prog);

VectorXd expected_answer(2);
expected_answer << 0.5, 0.5;
auto x_value = prog.GetSolution(x);
auto x_value = prog.GetSolution(x, result);
EXPECT_TRUE(CompareMatrices(expected_answer, x_value, 1e-10,
MatrixCompareType::absolute));

EXPECT_NEAR(0.5, prog.GetOptimalCost(), 1e-10);
EXPECT_NEAR(0.5, result.get_optimal_cost(), 1e-10);

// This problem is now an Equality Constrained QP and should
// use this solver:
CheckSolver(prog, EqualityConstrainedQPSolver::id());
EXPECT_EQ(result.get_solver_id(), EqualityConstrainedQPSolver::id());

// Add one more variable and constrain it in a different way
auto y = prog.NewContinuousVariables(1);
Expand All @@ -105,18 +106,18 @@ GTEST_TEST(testEqualityConstrainedQPSolver, testLinearlyConstrainedQPDispatch) {

prog.AddLinearConstraint(2 * x(0) - y(0) == 0);
prog.SetInitialGuessForAllVariables(Eigen::Vector3d::Zero());
prog.Solve();
result = Solve(prog, Eigen::Vector3d::Zero());
expected_answer.resize(3);
expected_answer << 0.5, 0.5, 1.0;
VectorXd actual_answer(3);
x_value = prog.GetSolution(x);
auto y_value = prog.GetSolution(y);
x_value = prog.GetSolution(x, result);
auto y_value = prog.GetSolution(y, result);
actual_answer << x_value, y_value;
EXPECT_TRUE(CompareMatrices(expected_answer, actual_answer, 1e-10,
MatrixCompareType::absolute))
<< "\tExpected: " << expected_answer.transpose()
<< "\tActual: " << actual_answer.transpose();
EXPECT_NEAR(0.5, prog.GetOptimalCost(), 1e-10);
EXPECT_NEAR(0.5, result.get_optimal_cost(), 1e-10);
}

GTEST_TEST(testEqualityConstrainedQPSolver,
Expand Down Expand Up @@ -348,11 +349,13 @@ GTEST_TEST(testEqualityConstrainedQPSolver, testLinearCost) {
prog.AddQuadraticCost(x.transpose() * x);
prog.AddLinearCost(x(0) + x(1) + 1);

EXPECT_EQ(prog.Solve(), SolutionResult::kSolutionFound);
MathematicalProgramResult result;
result = Solve(prog);
EXPECT_EQ(result.get_solution_result(), SolutionResult::kSolutionFound);

EXPECT_TRUE(
CompareMatrices(prog.GetSolution(x), Eigen::Vector2d(-.5, -.5), 1e-6));
EXPECT_EQ(prog.GetOptimalCost(), .5);
EXPECT_TRUE(CompareMatrices(prog.GetSolution(x, result),
Eigen::Vector2d(-.5, -.5), 1e-6));
EXPECT_EQ(result.get_optimal_cost(), .5);
}

class EqualityConstrainedQPSolverTest : public ::testing::Test {
Expand Down
Loading

0 comments on commit b9e9c4f

Please sign in to comment.