Skip to content

Commit

Permalink
Change ProgramAttribute to enum class, add ChooseBestSolver. (RobotLo…
Browse files Browse the repository at this point in the history
…comotion#9866)

Change ProgramAttribute to enum class, add ChooseBestSolver.
  • Loading branch information
hongkai-dai authored Nov 1, 2018
1 parent 3949328 commit 549f822
Show file tree
Hide file tree
Showing 48 changed files with 711 additions and 163 deletions.
44 changes: 44 additions & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ drake_cc_package_library(
":bilinear_product_util",
":binding",
":branch_and_bound",
":choose_best_solver",
":constraint",
":cost",
":create_constraint",
Expand All @@ -49,6 +50,7 @@ drake_cc_package_library(
":nlopt_solver",
":non_convex_optimization_util",
":osqp_solver",
":program_attribute",
":rotation_constraint",
":scs_solver",
":snopt_solver",
Expand Down Expand Up @@ -92,6 +94,27 @@ drake_cc_library(
],
)

drake_cc_library(
name = "choose_best_solver",
srcs = ["choose_best_solver.cc"],
hdrs = ["choose_best_solver.h"],
deps = [
":dreal_solver",
":equality_constrained_qp_solver",
":gurobi_solver",
":ipopt_solver",
":linear_system_solver",
":mathematical_program_api",
":moby_lcp_solver",
":mosek_solver",
":nlopt_solver",
":osqp_solver",
":scs_solver",
":snopt_solver",
":solver_id",
],
)

drake_cc_library(
name = "evaluator_base",
srcs = ["evaluator_base.cc"],
Expand Down Expand Up @@ -253,6 +276,7 @@ drake_cc_library(
hdrs = [],
deps = [
":binding",
":choose_best_solver",
":create_constraint",
":create_cost",
":decision_variable",
Expand All @@ -267,6 +291,7 @@ drake_cc_library(
":mosek_solver",
":nlopt_solver",
":osqp_solver",
":program_attribute",
":scs_solver",
":snopt_solver",
":solution_result",
Expand Down Expand Up @@ -376,6 +401,15 @@ drake_cc_library(
],
)

drake_cc_library(
name = "program_attribute",
srcs = ["program_attribute.cc"],
hdrs = ["program_attribute.h"],
deps = [
"//common:hash",
],
)

drake_cc_library(
name = "rotation_constraint_visualization",
testonly = 1,
Expand Down Expand Up @@ -541,6 +575,7 @@ drake_cc_library(
":function",
":indeterminate",
":mathematical_program_result",
":program_attribute",
":solution_result",
":solver_id",
":solver_result",
Expand Down Expand Up @@ -1417,6 +1452,15 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "choose_best_solver_test",
deps = [
":choose_best_solver",
":mathematical_program",
"//common/test_utilities:expect_throws_message",
],
)

# The extra_srcs are required here because add_lint_tests() doesn't understand
# how to extract labels from select() functions yet.
add_lint_tests(cpplint_extra_srcs = [
Expand Down
60 changes: 60 additions & 0 deletions solvers/choose_best_solver.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
#include "drake/solvers/choose_best_solver.h"

#include "drake/solvers/dreal_solver.h"
#include "drake/solvers/equality_constrained_qp_solver.h"
#include "drake/solvers/gurobi_solver.h"
#include "drake/solvers/ipopt_solver.h"
#include "drake/solvers/linear_system_solver.h"
#include "drake/solvers/moby_lcp_solver.h"
#include "drake/solvers/mosek_solver.h"
#include "drake/solvers/nlopt_solver.h"
#include "drake/solvers/osqp_solver.h"
#include "drake/solvers/scs_solver.h"
#include "drake/solvers/snopt_solver.h"

namespace drake {
namespace solvers {
SolverId ChooseBestSolver(const MathematicalProgram& prog) {
if (LinearSystemSolver::is_available() &&
LinearSystemSolver::ProgramAttributesSatisfied(prog)) {
return LinearSystemSolver::id();
} else if (EqualityConstrainedQPSolver::is_available() &&
EqualityConstrainedQPSolver::ProgramAttributesSatisfied(prog)) {
return EqualityConstrainedQPSolver::id();
} else if (MosekSolver::is_available() &&
MosekSolver::ProgramAttributesSatisfied(prog)) {
// TODO([email protected]): based on my limited experience, Mosek is
// faster than Gurobi for convex optimization problem. But we should run
// a more thorough comparison.
return MosekSolver::id();
} else if (GurobiSolver::is_available() &&
GurobiSolver::ProgramAttributesSatisfied(prog)) {
return GurobiSolver::id();
} else if (OsqpSolver::is_available() &&
OsqpSolver::ProgramAttributesSatisfied(prog)) {
return OsqpSolver::id();
} else if (MobyLCPSolver<double>::is_available() &&
MobyLCPSolver<double>::ProgramAttributesSatisfied(prog)) {
return MobyLcpSolverId::id();
} else if (SnoptSolver::is_available() &&
SnoptSolver::ProgramAttributesSatisfied(prog)) {
return SnoptSolver::id();
} else if (IpoptSolver::is_available() &&
IpoptSolver::ProgramAttributesSatisfied(prog)) {
return IpoptSolver::id();
} else if (NloptSolver::is_available() &&
NloptSolver::ProgramAttributesSatisfied(prog)) {
return NloptSolver::id();
} else if (ScsSolver::is_available() &&
ScsSolver::ProgramAttributesSatisfied(prog)) {
// Use SCS as the last resort. SCS uses ADMM method, which converges fast to
// modest accuracy quite fast, but then slows down significantly if the user
// wants high accuracy.
return ScsSolver::id();
}

throw std::invalid_argument(
"There is no available solver for the optimization program");
}
} // namespace solvers
} // namespace drake
15 changes: 15 additions & 0 deletions solvers/choose_best_solver.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
#pragma once

#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/solver_id.h"

namespace drake {
namespace solvers {
/**
* Choose the best solver given the formulation in the optimization program and
* the availability of the solvers.
* @throw invalid_argument if there is no available solver for @p prog.
*/
SolverId ChooseBestSolver(const MathematicalProgram& prog);
} // namespace solvers
} // namespace drake
2 changes: 1 addition & 1 deletion solvers/dreal_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -416,7 +416,7 @@ optional<DrealSolver::IntervalBox> DrealSolver::Minimize(
}
}

bool DrealSolver::available() const { return true; }
bool DrealSolver::is_available() { return true; }

namespace {

Expand Down
9 changes: 8 additions & 1 deletion solvers/dreal_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@ class DrealSolver : public MathematicalProgramSolverInterface {

// This solver is implemented in various pieces depending on if
// Dreal was available during compilation.
bool available() const override;
bool available() const override { return is_available(); };

static bool is_available();

SolutionResult Solve(MathematicalProgram& prog) const override;

Expand All @@ -41,6 +43,11 @@ class DrealSolver : public MathematicalProgramSolverInterface {
/// @return same as MathematicalProgramSolverInterface::solver_id()
static SolverId id();

bool AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const override;

static bool ProgramAttributesSatisfied(const MathematicalProgram& prog);

/// Checks the satisfiability of a given formula @p f with a given precision
/// @p delta.
///
Expand Down
21 changes: 21 additions & 0 deletions solvers/dreal_solver_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
/* clang-format on */

#include "drake/common/never_destroyed.h"
#include "drake/solvers/mathematical_program.h"

// This file contains implementations that are common to both the available and
// unavailable flavor of this class.
Expand All @@ -19,5 +20,25 @@ SolverId DrealSolver::id() {
return singleton.access();
}

bool DrealSolver::AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const {
return DrealSolver::ProgramAttributesSatisfied(prog);
}

bool DrealSolver::ProgramAttributesSatisfied(const MathematicalProgram& prog) {
static const never_destroyed<ProgramAttributes> solver_capabilities(
std::initializer_list<ProgramAttribute>{
ProgramAttribute::kGenericConstraint,
ProgramAttribute::kLinearEqualityConstraint,
ProgramAttribute::kLinearConstraint,
ProgramAttribute::kLorentzConeConstraint,
ProgramAttribute::kRotatedLorentzConeConstraint,
ProgramAttribute::kLinearComplementarityConstraint,
ProgramAttribute::kLinearCost, ProgramAttribute::kQuadraticCost,
ProgramAttribute::kBinaryVariable});
return AreRequiredAttributesSupported(prog.required_capabilities(),
solver_capabilities.access());
}

} // namespace solvers
} // namespace drake
19 changes: 18 additions & 1 deletion solvers/equality_constrained_qp_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
namespace drake {
namespace solvers {

bool EqualityConstrainedQPSolver::available() const { return true; }
bool EqualityConstrainedQPSolver::is_available() { return true; }

/**
* Solves the un-constrained QP problem
Expand Down Expand Up @@ -279,5 +279,22 @@ SolverId EqualityConstrainedQPSolver::id() {
return singleton.access();
}

bool EqualityConstrainedQPSolver::AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const {
return ProgramAttributesSatisfied(prog);
}

bool EqualityConstrainedQPSolver::ProgramAttributesSatisfied(
const MathematicalProgram& prog) {
static const never_destroyed<ProgramAttributes> solver_capabilities(
std::initializer_list<ProgramAttribute>{
ProgramAttribute::kQuadraticCost, ProgramAttribute::kLinearCost,
ProgramAttribute::kLinearEqualityConstraint});
// TODO(hongkai.dai) also make sure that there exists at least a quadratic
// cost.
return AreRequiredAttributesSupported(prog.required_capabilities(),
solver_capabilities.access());
}

} // namespace solvers
} // namespace drake
9 changes: 8 additions & 1 deletion solvers/equality_constrained_qp_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,9 @@ class EqualityConstrainedQPSolver : public MathematicalProgramSolverInterface {
EqualityConstrainedQPSolver() = default;
~EqualityConstrainedQPSolver() override = default;

bool available() const override;
bool available() const override { return is_available(); };

static bool is_available();

/**
* Solve the qudratic program with equality constraint.
Expand All @@ -30,6 +32,11 @@ class EqualityConstrainedQPSolver : public MathematicalProgramSolverInterface {

/// @return same as MathematicalProgramSolverInterface::solver_id()
static SolverId id();

bool AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const override;

static bool ProgramAttributesSatisfied(const MathematicalProgram& prog);
};

} // namespace solvers
Expand Down
2 changes: 1 addition & 1 deletion solvers/gurobi_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -604,7 +604,7 @@ void AddSecondOrderConeVariables(
}
} // anonymous namespace

bool GurobiSolver::available() const { return true; }
bool GurobiSolver::is_available() { return true; }

/*
* Implements RAII for a Gurobi license / environment.
Expand Down
9 changes: 8 additions & 1 deletion solvers/gurobi_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@ class GurobiSolver : public MathematicalProgramSolverInterface {

// This solver is implemented in various pieces depending on if
// Gurobi was available during compilation.
bool available() const override;
bool available() const override { return is_available(); };

static bool is_available();

/// Contains info returned to a user function that handles
/// a Node or Solution callback.
Expand Down Expand Up @@ -111,6 +113,11 @@ class GurobiSolver : public MathematicalProgramSolverInterface {
/// @return same as MathematicalProgramSolverInterface::solver_id()
static SolverId id();

bool AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const override;

static bool ProgramAttributesSatisfied(const MathematicalProgram& prog);

/**
* This type contains a valid Gurobi license environment, and is only to be
* used from AcquireLicense().
Expand Down
19 changes: 19 additions & 0 deletions solvers/gurobi_solver_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
/* clang-format on */

#include "drake/common/never_destroyed.h"
#include "drake/solvers/mathematical_program.h"

// This file contains implementations that are common to both the available and
// unavailable flavor of this class.
Expand All @@ -19,5 +20,23 @@ SolverId GurobiSolver::id() {
return singleton.access();
}

bool GurobiSolver::AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const {
return GurobiSolver::ProgramAttributesSatisfied(prog);
}

bool GurobiSolver::ProgramAttributesSatisfied(const MathematicalProgram& prog) {
// TODO(hongkai.dai): Gurobi supports callback. Add callback capability.
static const never_destroyed<ProgramAttributes> solver_capabilities(
std::initializer_list<ProgramAttribute>{
ProgramAttribute::kLinearCost, ProgramAttribute::kQuadraticCost,
ProgramAttribute::kLinearConstraint,
ProgramAttribute::kLinearEqualityConstraint,
ProgramAttribute::kLorentzConeConstraint,
ProgramAttribute::kRotatedLorentzConeConstraint,
ProgramAttribute::kBinaryVariable});
return AreRequiredAttributesSupported(prog.required_capabilities(),
solver_capabilities.access());
}
} // namespace solvers
} // namespace drake
2 changes: 1 addition & 1 deletion solvers/ipopt_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -502,7 +502,7 @@ class IpoptSolver_NLP : public Ipopt::TNLP {

} // namespace

bool IpoptSolver::available() const { return true; }
bool IpoptSolver::is_available() { return true; }

SolutionResult IpoptSolver::Solve(MathematicalProgram& prog) const {
DRAKE_ASSERT(prog.linear_complementarity_constraints().empty());
Expand Down
9 changes: 8 additions & 1 deletion solvers/ipopt_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,21 @@ class IpoptSolver : public MathematicalProgramSolverInterface {

// This solver is implemented in various pieces depending on if
// Ipopt was available during compilation.
bool available() const override;
bool available() const override { return is_available(); };

static bool is_available();

SolutionResult Solve(MathematicalProgram& prog) const override;

SolverId solver_id() const override;

/// @return same as MathematicalProgramSolverInterface::solver_id()
static SolverId id();

bool AreProgramAttributesSatisfied(
const MathematicalProgram& prog) const override;

static bool ProgramAttributesSatisfied(const MathematicalProgram& prog);
};

} // namespace solvers
Expand Down
Loading

0 comments on commit 549f822

Please sign in to comment.