Skip to content

Commit

Permalink
Mosek supports exponential cone. (RobotLocomotion#11755)
Browse files Browse the repository at this point in the history
Mosek supports exponential cone.
  • Loading branch information
hongkai-dai authored Jul 8, 2019
1 parent 7b257f3 commit b50632d
Show file tree
Hide file tree
Showing 4 changed files with 62 additions and 12 deletions.
1 change: 1 addition & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -1365,6 +1365,7 @@ drake_cc_googletest(
tags = mosek_test_tags(),
use_default_main = False,
deps = [
":exponential_cone_program_examples",
":linear_program_examples",
":mathematical_program_private",
":mathematical_program_test_util",
Expand Down
50 changes: 38 additions & 12 deletions solvers/mosek_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -512,20 +512,22 @@ MSKrescodee AddBoundingBoxConstraints(
}

/*
* This is the helper function to add two types of second order cone
* constraints:
* This is the helper function to add three types of conic constraints
* 1. A Lorentz cone constraint:
* z = A*x+b
* z0 >= sqrt(z1^2 + .. zN^2)
* 2. A rotated Lorentz cone constraint:
* z = A*x+b
* z0*z1 >= z2^2 + .. + zN^2,
* z0 >= 0, z1 >=0
* 3. An exonential cone constraint:
* z = A*x+b
* z0 >= z1 * exp(z2 / z1)
* Mosek does not allow two cones to share variables. To overcome this,
* we will add a new set of variable (z0, ..., zN)
*/
template <typename C>
MSKrescodee AddSecondOrderConeConstraints(
MSKrescodee AddConeConstraints(
const MathematicalProgram& prog,
const std::vector<Binding<C>>& second_order_cone_constraints,
const std::unordered_map<int, MatrixVariableEntry>&
Expand All @@ -536,10 +538,12 @@ MSKrescodee AddSecondOrderConeConstraints(
matrix_variable_entry_to_selection_matrix_id,
MSKtask_t* task) {
static_assert(std::is_same<C, LorentzConeConstraint>::value ||
std::is_same<C, RotatedLorentzConeConstraint>::value,
"Should be either Lorentz cone constraint or rotated Lorentz "
"cone constraint");
bool is_rotated_cone = std::is_same<C, RotatedLorentzConeConstraint>::value;
std::is_same<C, RotatedLorentzConeConstraint>::value ||
std::is_same<C, ExponentialConeConstraint>::value,
"Should be either Lorentz cone constraint, rotated Lorentz "
"cone or exponential cone constraint");
const bool is_rotated_cone =
std::is_same<C, RotatedLorentzConeConstraint>::value;
MSKrescodee rescode = MSK_RES_OK;
for (auto const& binding : second_order_cone_constraints) {
const auto& A = binding.evaluator()->A();
Expand All @@ -563,7 +567,16 @@ MSKrescodee AddSecondOrderConeConstraints(
return rescode;
}
}
MSKconetypee cone_type = is_rotated_cone ? MSK_CT_RQUAD : MSK_CT_QUAD;
MSKconetypee cone_type;
if (std::is_same<C, LorentzConeConstraint>::value) {
cone_type = MSK_CT_QUAD;
} else if (std::is_same<C, RotatedLorentzConeConstraint>::value) {
cone_type = MSK_CT_RQUAD;
} else if (std::is_same<C, ExponentialConeConstraint>::value) {
cone_type = MSK_CT_PEXP;
} else {
DRAKE_UNREACHABLE();
}
rescode =
MSK_appendcone(*task, cone_type, 0.0, num_z, new_var_indices.data());
if (rescode != MSK_RES_OK) {
Expand All @@ -580,7 +593,7 @@ MSKrescodee AddSecondOrderConeConstraints(
// So there is a factor of 2 for rotated Lorentz cone.
// With this difference in rotated Lorentz cone, the first row of constraint
// z = A * x + b needs special treatment.
// If using Lorentz cone,
// If using Lorentz cone or exponential cone,
// Add the linear constraint
// z0 = a0^T * x + b0;
// If using rotated Lorentz cone, add the linear constraint
Expand Down Expand Up @@ -1177,6 +1190,7 @@ MSKrescodee AddEqualityConstraintBetweenMatrixVariablesForSameDecisionVariable(
}
return rescode;
}

} // anonymous namespace

/*
Expand Down Expand Up @@ -1365,7 +1379,7 @@ void MosekSolver::DoSolve(const MathematicalProgram& prog,

// Add Lorentz cone constraints.
if (rescode == MSK_RES_OK) {
rescode = AddSecondOrderConeConstraints(
rescode = AddConeConstraints(
prog, prog.lorentz_cone_constraints(),
decision_variable_index_to_mosek_matrix_variable,
decision_variable_index_to_mosek_nonmatrix_variable,
Expand All @@ -1374,7 +1388,7 @@ void MosekSolver::DoSolve(const MathematicalProgram& prog,

// Add rotated Lorentz cone constraints.
if (rescode == MSK_RES_OK) {
rescode = AddSecondOrderConeConstraints(
rescode = AddConeConstraints(
prog, prog.rotated_lorentz_cone_constraints(),
decision_variable_index_to_mosek_matrix_variable,
decision_variable_index_to_mosek_nonmatrix_variable,
Expand All @@ -1388,6 +1402,17 @@ void MosekSolver::DoSolve(const MathematicalProgram& prog,
decision_variable_index_to_mosek_nonmatrix_variable,
&matrix_variable_entry_to_selection_matrix_id, &task);
}

// Add exponential cone constraints.
if (rescode == MSK_RES_OK) {
rescode = AddConeConstraints(
prog, prog.exponential_cone_constraints(),
decision_variable_index_to_mosek_matrix_variable,
decision_variable_index_to_mosek_nonmatrix_variable,
&matrix_variable_entry_to_selection_matrix_id, &task);
}

// log file.
if (rescode == MSK_RES_OK && stream_logging_) {
if (log_file_.empty()) {
rescode =
Expand Down Expand Up @@ -1443,7 +1468,8 @@ void MosekSolver::DoSolve(const MathematicalProgram& prog,
prog.lorentz_cone_constraints().empty() &&
prog.rotated_lorentz_cone_constraints().empty() &&
prog.positive_semidefinite_constraints().empty() &&
prog.linear_matrix_inequality_constraints().empty()) {
prog.linear_matrix_inequality_constraints().empty() &&
prog.exponential_cone_constraints().empty()) {
solution_type = MSK_SOL_BAS;
} else {
solution_type = MSK_SOL_ITR;
Expand Down
1 change: 1 addition & 0 deletions solvers/mosek_solver_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ bool MosekSolver::ProgramAttributesSatisfied(const MathematicalProgram& prog) {
ProgramAttribute::kLorentzConeConstraint,
ProgramAttribute::kRotatedLorentzConeConstraint,
ProgramAttribute::kPositiveSemidefiniteConstraint,
ProgramAttribute::kExponentialConeConstraint,
ProgramAttribute::kLinearCost, ProgramAttribute::kQuadraticCost,
ProgramAttribute::kBinaryVariable});
return AreRequiredAttributesSupported(prog.required_capabilities(),
Expand Down
22 changes: 22 additions & 0 deletions solvers/test/mosek_solver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include "drake/common/temp_directory.h"
#include "drake/solvers/mathematical_program.h"
#include "drake/solvers/mixed_integer_optimization_util.h"
#include "drake/solvers/test/exponential_cone_program_examples.h"
#include "drake/solvers/test/linear_program_examples.h"
#include "drake/solvers/test/quadratic_program_examples.h"
#include "drake/solvers/test/second_order_cone_program_examples.h"
Expand Down Expand Up @@ -178,6 +179,27 @@ GTEST_TEST(TestSemidefiniteProgram, SolveSDPwithOverlappingVariables) {
}
}

GTEST_TEST(TestExponentialConeProgram, ExponentialConeTrivialExample) {
MosekSolver solver;
if (solver.available()) {
ExponentialConeTrivialExample(solver, 1E-5);
}
}

GTEST_TEST(TestExponentialConeProgram, MinimizeKLDivengence) {
MosekSolver solver;
if (solver.available()) {
MinimizeKLDivergence(solver, 2E-5);
}
}

GTEST_TEST(TestExponentialConeProgram, MinimalEllipsoidConveringPoints) {
MosekSolver solver;
if (solver.available()) {
MinimalEllipsoidCoveringPoints(solver, 1E-6);
}
}

GTEST_TEST(MosekTest, TestLogFile) {
// Test if we can print the logging info to a log file.
MathematicalProgram prog;
Expand Down

0 comments on commit b50632d

Please sign in to comment.