Skip to content

Commit

Permalink
solvers: Port MosekSolver and GurobiSolver to SolverBase (RobotLocomo…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Feb 13, 2019
1 parent 4bb800e commit 420bee8
Show file tree
Hide file tree
Showing 10 changed files with 98 additions and 164 deletions.
4 changes: 4 additions & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -674,13 +674,15 @@ drake_cc_library(
deps = select({
"//tools:with_gurobi": [
":mathematical_program_lite",
":solver_base",
"//math:eigen_sparse_triplet",
"//common:scoped_singleton",
"@gurobi//:gurobi_c",
"@fmt",
],
"//conditions:default": [
":mathematical_program_lite",
":solver_base",
],
}),
)
Expand All @@ -705,12 +707,14 @@ drake_cc_library(
"//tools:with_mosek": [
":mathematical_program_lite",
":mathematical_program_result",
":solver_base",
"//common:scoped_singleton",
"@mosek",
],
"//conditions:default": [
":mathematical_program_lite",
":mathematical_program_result",
":solver_base",
],
}),
)
Expand Down
54 changes: 15 additions & 39 deletions solvers/gurobi_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -653,22 +653,15 @@ std::shared_ptr<GurobiSolver::License> GurobiSolver::AcquireLicense() {
return GetScopedSingleton<GurobiSolver::License>();
}

void GurobiSolver::Solve(const MathematicalProgram& prog,
const optional<Eigen::VectorXd>& initial_guess,
const optional<SolverOptions>& solver_options,
MathematicalProgramResult* result) const {
// reset result.
*result = {};
result->set_decision_variable_index(prog.decision_variable_index());
void GurobiSolver::DoSolve(
const MathematicalProgram& prog,
const Eigen::VectorXd& initial_guess,
const SolverOptions& merged_options,
MathematicalProgramResult* result) const {
if (!license_) {
license_ = AcquireLicense();
}
GRBenv* env = license_->GurobiEnv();
if (!AreProgramAttributesSatisfied(prog)) {
throw std::invalid_argument(
"GurobiSolver's capability doesn't satisfy the requirement of this "
"optimization program.");
}

const int num_prog_vars = prog.num_vars();
int num_gurobi_vars = num_prog_vars;
Expand Down Expand Up @@ -797,40 +790,25 @@ void GurobiSolver::Solve(const MathematicalProgram& prog,
error = GRBsetintparam(model_env, GRB_INT_PAR_OUTPUTFLAG, 0);
}

for (const auto it : prog.GetSolverOptionsDouble(id())) {
for (const auto it : merged_options.GetOptionsDouble(id())) {
if (!error) {
error = GRBsetdblparam(model_env, it.first.c_str(), it.second);
}
}
for (const auto it : prog.GetSolverOptionsInt(id())) {
for (const auto it : merged_options.GetOptionsInt(id())) {
if (!error) {
error = GRBsetintparam(model_env, it.first.c_str(), it.second);
}
}
if (solver_options.has_value()) {
for (const auto it : solver_options->GetOptionsDouble(id())) {
if (!error) {
error = GRBsetdblparam(model_env, it.first.c_str(), it.second);
}
}
for (const auto it : solver_options->GetOptionsInt(id())) {
if (!error) {
error = GRBsetintparam(model_env, it.first.c_str(), it.second);
}
}
}

if (initial_guess.has_value()) {
if (initial_guess.value().rows() != prog.num_vars()) {
throw std::invalid_argument(fmt::format(
"The initial guess has {} rows, but {} rows were expected.",
initial_guess.value().rows(), prog.num_vars()));
}
for (int i = 0; i < static_cast<int>(prog.num_vars()); ++i) {
if (!error) {
error =
GRBsetdblattrelement(model, "Start", i, initial_guess.value()(i));
}
if (initial_guess.rows() != prog.num_vars()) {
throw std::invalid_argument(fmt::format(
"The initial guess has {} rows, but {} rows were expected.",
initial_guess.rows(), prog.num_vars()));
}
for (int i = 0; i < static_cast<int>(prog.num_vars()); ++i) {
if (!error && !std::isnan(initial_guess(i))) {
error = GRBsetdblattrelement(model, "Start", i, initial_guess(i));
}
}

Expand Down Expand Up @@ -860,8 +838,6 @@ void GurobiSolver::Solve(const MathematicalProgram& prog,
error = GRBoptimize(model);
}

result->set_solver_id(GurobiSolver::id());

SolutionResult solution_result = SolutionResult::kUnknownError;

GurobiSolverDetails& solver_details =
Expand Down
45 changes: 19 additions & 26 deletions solvers/gurobi_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include "drake/common/autodiff.h"
#include "drake/common/drake_copyable.h"
#include "drake/solvers/decision_variable.h"
#include "drake/solvers/solver_interface.h"
#include "drake/solvers/solver_base.h"

namespace drake {
namespace solvers {
Expand All @@ -31,18 +31,12 @@ struct GurobiSolverDetails {
double objective_bound{NAN};
};

class GurobiSolver : public SolverInterface {
class GurobiSolver final : public SolverBase {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(GurobiSolver)

GurobiSolver() = default;
~GurobiSolver() override = default;

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

static bool is_available();
GurobiSolver();
~GurobiSolver() final;

/// Contains info returned to a user function that handles
/// a Node or Solution callback.
Expand Down Expand Up @@ -125,22 +119,6 @@ class GurobiSolver : public SolverInterface {
mip_sol_callback_ = callback;
}

SolutionResult Solve(MathematicalProgram& prog) const override;

void Solve(const MathematicalProgram&, const optional<Eigen::VectorXd>&,
const optional<SolverOptions>&,
MathematicalProgramResult*) const override;

SolverId solver_id() const override;

/// @return same as SolverInterface::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 All @@ -163,7 +141,22 @@ class GurobiSolver : public SolverInterface {
*/
static std::shared_ptr<License> AcquireLicense();

/// @name Static versions of the instance methods of the same name.
//@{
static SolverId id();
static bool is_available();
static bool ProgramAttributesSatisfied(const MathematicalProgram&);
//@}

// A using-declaration adds these methods into our class's Doxygen.
using SolverBase::Solve;
// NOLINTNEXTLINE(runtime/references)
SolutionResult Solve(MathematicalProgram&) const final;

private:
void DoSolve(const MathematicalProgram&, const Eigen::VectorXd&,
const SolverOptions&, MathematicalProgramResult*) const final;

// Note that this is mutable to allow latching the allocation of env_
// during the first call of Solve() (which avoids grabbing a Gurobi license
// before we know that we actually want one).
Expand Down
12 changes: 4 additions & 8 deletions solvers/gurobi_solver_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,20 +11,16 @@
namespace drake {
namespace solvers {

SolverId GurobiSolver::solver_id() const {
return id();
}
GurobiSolver::GurobiSolver()
: SolverBase(&id, &is_available, &ProgramAttributesSatisfied) {}

GurobiSolver::~GurobiSolver() = default;

SolverId GurobiSolver::id() {
static const never_destroyed<SolverId> singleton{"Gurobi"};
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(
Expand Down
41 changes: 17 additions & 24 deletions solvers/mosek_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -657,15 +657,11 @@ std::shared_ptr<MosekSolver::License> MosekSolver::AcquireLicense() {

bool MosekSolver::is_available() { return true; }

void MosekSolver::Solve(const MathematicalProgram& prog,
const optional<Eigen::VectorXd>& initial_guess,
const optional<SolverOptions>& solver_options,
MathematicalProgramResult* result) const {
*result = {};
result->set_decision_variable_index(prog.decision_variable_index());
SolverOptions merged_solver_options =
solver_options.value_or(SolverOptions());
merged_solver_options.Merge(prog.solver_options());
void MosekSolver::DoSolve(
const MathematicalProgram& prog,
const Eigen::VectorXd& initial_guess,
const SolverOptions& merged_options,
MathematicalProgramResult* result) const {
const int num_vars = prog.num_vars();
MSKtask_t task = nullptr;
MSKrescodee rescode;
Expand Down Expand Up @@ -744,29 +740,35 @@ void MosekSolver::Solve(const MathematicalProgram& prog,

if (rescode == MSK_RES_OK) {
for (const auto& double_options :
merged_solver_options.GetOptionsDouble(id())) {
merged_options.GetOptionsDouble(id())) {
if (rescode == MSK_RES_OK) {
rescode = MSK_putnadouparam(task, double_options.first.c_str(),
double_options.second);
}
}
for (const auto& int_options : merged_solver_options.GetOptionsInt(id())) {
for (const auto& int_options : merged_options.GetOptionsInt(id())) {
if (rescode == MSK_RES_OK) {
rescode = MSK_putnaintparam(task, int_options.first.c_str(),
int_options.second);
}
}
for (const auto& str_options : merged_solver_options.GetOptionsStr(id())) {
for (const auto& str_options : merged_options.GetOptionsStr(id())) {
if (rescode == MSK_RES_OK) {
rescode = MSK_putnastrparam(task, str_options.first.c_str(),
str_options.second.c_str());
}
}
}

if (with_integer_or_binary_variable && initial_guess.has_value()) {
// Mosek can accept the initial guess on its integer/binary variables, but
// not on the continuous variables. So it allows some of the variables'
// initial guess to be unset, while setting the others. If the initial guess
// for any variable is finite, then we ask Mosek to set the initial guess.
const bool has_any_finite_initial_guess =
initial_guess.unaryExpr([](double g) { return std::isfinite(g); }).any();
if (with_integer_or_binary_variable && has_any_finite_initial_guess) {
// Set the initial guess for the integer/binary variables.
DRAKE_ASSERT(initial_guess->size() == prog.num_vars());
DRAKE_ASSERT(initial_guess.size() == prog.num_vars());
MSKint32t num_mosek_vars{0};
if (rescode == MSK_RES_OK) {
// num_mosek_vars is guaranteed to be no less than prog.num_vars(), as we
Expand All @@ -785,7 +787,7 @@ void MosekSolver::Solve(const MathematicalProgram& prog,
if (var_type == MathematicalProgram::VarType::INTEGER ||
var_type == MathematicalProgram::VarType::BINARY) {
if (rescode == MSK_RES_OK) {
const MSKrealt initial_guess_i = initial_guess.value()(var_count);
const MSKrealt initial_guess_i = initial_guess(var_count);
rescode =
MSK_putxxslice(task, MSK_SOL_ITG, i, i + 1, &initial_guess_i);
}
Expand Down Expand Up @@ -820,7 +822,6 @@ void MosekSolver::Solve(const MathematicalProgram& prog,
solution_type = MSK_SOL_ITR;
}

result->set_solver_id(id());
// TODO([email protected]) : Add MOSEK parameters.
// Mosek parameter are added by enum, not by string.
MSKsolstae solution_status{MSK_SOL_STA_UNKNOWN};
Expand Down Expand Up @@ -895,13 +896,5 @@ void MosekSolver::Solve(const MathematicalProgram& prog,
MSK_deletetask(&task);
}

SolutionResult MosekSolver::Solve(MathematicalProgram& prog) const {
MathematicalProgramResult result;
Solve(prog, {}, {}, &result);
const SolverResult solver_result = result.ConvertToSolverResult();
prog.SetSolverResult(solver_result);
return result.get_solution_result();
}

} // namespace solvers
} // namespace drake
Loading

0 comments on commit 420bee8

Please sign in to comment.