Skip to content

Commit

Permalink
Throw an error when getting dual solution for a QCP in gurobi. (Robot…
Browse files Browse the repository at this point in the history
…Locomotion#14285)

* Throw an error when getting dual solution for a QCP in gurobi.
  • Loading branch information
hongkai-dai authored Nov 5, 2020
1 parent 0c5affa commit 24b73e7
Show file tree
Hide file tree
Showing 3 changed files with 49 additions and 19 deletions.
31 changes: 20 additions & 11 deletions solvers/gurobi_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1105,8 +1105,21 @@ void GurobiSolver::DoSolve(
&prog_sol_vector);
result->set_x_val(prog_sol_vector);

// If QCPDual is 0 and the program has quadratic constraints (including
// both Lorentz cone and rotated Lorentz cone constraints), then the dual
// variables are not computed.
int qcp_dual;
error = GRBgetintparam(model_env, "QCPDual", &qcp_dual);
DRAKE_DEMAND(!error);

int num_q_constrs = 0;
error = GRBgetintattr(model, "NumQConstrs", &num_q_constrs);
DRAKE_DEMAND(!error);

const bool compute_dual = !(num_q_constrs > 0 && qcp_dual == 0);

// Set dual solutions.
if (!is_mip) {
if (!is_mip && compute_dual) {
// Gurobi only provides dual solution for continuous models.
// Gurobi stores its dual solution for each variable bounds in "reduced
// cost".
Expand All @@ -1115,18 +1128,14 @@ void GurobiSolver::DoSolve(
reduced_cost.data());
SetBoundingBoxDualSolution(prog, reduced_cost, bb_con_dual_indices,
result);
}

Eigen::VectorXd gurobi_dual_solutions(num_gurobi_linear_constraints);
GRBgetdblattrarray(model, GRB_DBL_ATTR_PI, 0,
num_gurobi_linear_constraints,
gurobi_dual_solutions.data());
SetLinearConstraintDualSolutions(prog, gurobi_dual_solutions,
constraint_dual_start_row, result);
Eigen::VectorXd gurobi_dual_solutions(num_gurobi_linear_constraints);
GRBgetdblattrarray(model, GRB_DBL_ATTR_PI, 0,
num_gurobi_linear_constraints,
gurobi_dual_solutions.data());
SetLinearConstraintDualSolutions(prog, gurobi_dual_solutions,
constraint_dual_start_row, result);

int compute_qcp_dual;
error = GRBgetintparam(model_env, "QCPDual", &compute_qcp_dual);
if (compute_qcp_dual) {
SetAllSecondOrderConeDualSolution(prog, model, result);
}

Expand Down
18 changes: 10 additions & 8 deletions solvers/mathematical_program_result.h
Original file line number Diff line number Diff line change
Expand Up @@ -305,15 +305,17 @@ class MathematicalProgramResult final {
auto it = dual_solutions_.find(constraint_cast);
if (it == dual_solutions_.end()) {
// Throws a more meaningful error message when the user wants to retrieve
// dual solution for second order cone constraint from Gurobi result, but
// forgot to explicitly turn on the flag to compute gurobi qcp dual.
if constexpr (std::is_same<C, LorentzConeConstraint>::value ||
std::is_same<C, RotatedLorentzConeConstraint>::value) {
// a dual solution from a Gurobi result for a program containing second
// order cone constraints, but forgot to explicitly turn on the flag to
// compute Gurobi QCP dual.
if (solver_id_.name() == "Gurobi") {
throw std::invalid_argument(fmt::format(
"You used {} to solve this optimization problem. If the solver is "
"Gurobi, you have to explicitly tell Gurobi solver to compute the "
"dual solution for the second order cone constraints by setting "
"the solver options. One example is as follows: "
"You used {} to solve this optimization problem. If the problem is "
"solved to optimality and doesn't contain binary/integer "
"variables, but you failed to get the dual solution, "
"check that you have explicitly told Gurobi solver to "
"compute the dual solution for the second order cone constraints "
"by setting the solver options. One example is as follows: "
"SolverOptions options; "
"options.SetOption(GurobiSolver::id(), \"QCPDual\", 1); "
"auto result=Solve(prog, std::nullopt, options);",
Expand Down
19 changes: 19 additions & 0 deletions solvers/test/gurobi_solver_test.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "drake/solvers/gurobi_solver.h"

#include <limits>
#include <thread>

#include <gtest/gtest.h>
Expand All @@ -15,6 +16,7 @@
namespace drake {
namespace solvers {
namespace test {
const double kInf = std::numeric_limits<double>::infinity();

TEST_P(LinearProgramTest, TestLP) {
GurobiSolver solver;
Expand Down Expand Up @@ -460,6 +462,23 @@ GTEST_TEST(GurobiTest, SOCPDualSolution1) {
// cost (-sqrt(4 + eps) - 1)/3 w.r.t eps is -1/12.
EXPECT_TRUE(CompareMatrices(result.GetDualSolution(constraint1),
Vector1d(-1. / 12), 1e-7));

// Now add a bounding box constraint to the program. By setting QCPDual to
// 0, the program should throw an error.
auto bb_con = prog.AddBoundingBoxConstraint(0, kInf, x(1));
options.SetOption(solver.id(), "QCPDual", 0);
result = solver.Solve(prog, std::nullopt, options);
DRAKE_EXPECT_THROWS_MESSAGE(
result.GetDualSolution(bb_con), std::invalid_argument,
"You used Gurobi to solve this optimization problem.*");
// Now set QCPDual = 1, we should be able to retrieve the dual solution to
// the bounding box constraint.
options.SetOption(solver.id(), "QCPDual", 1);
result = solver.Solve(prog, std::nullopt, options);
// The cost is x(1), hence the shadow price for the constraint x(1) >= 0
// should be 1.
EXPECT_TRUE(
CompareMatrices(result.GetDualSolution(bb_con), Vector1d(1.), 1E-8));
}
}

Expand Down

0 comments on commit 24b73e7

Please sign in to comment.