Drake
Formulating and Solving Optimization Problems

Detailed Description

Drake's MathematicalProgram class is used to solve the mathematical optimization problem in the following form.

  minₓ f(x)
  s.t x ∈ S

Depending on the formulation of the objective function f, and the structure of the constraint set S, this optimization problem can be grouped into different categories (linear programming, quadratic programming, nonconvex nonlinear programming, etc). Drake will call suitable solvers for each category of optimization problem.

Drake wraps a number of commercial solvers (+ a few custom solvers) to provide a common interface for convex optimization, mixed-integer convex optimization, and other non-convex mathematical programs.

The MathematicalProgram class handles the coordination of decision variables, objectives, and constraints. The Solve() method reflects on the accumulated objectives and constraints and will dispatch to the most appropriate solver. Alternatively, one can invoke specific solver by instantiating its SolverInterface and passing the MathematicalProgram directly to the SolverInterface::Solve() method.

Our solver coverage still has many gaps, but is under active development.

Closed-form solutions When the mathematical problem is formulated as the following linear system

find x
s.t Ax = b

, then LinearSystemSolver provides efficient closed form solution.

When the mathematical problem is formulated as the following (convex) quadratic program with only linear equality constraint

min 0.5 xᵀHx + aᵀx + b
s.t Ax = b

, then EqualityConstraintQPSolver provides efficient closed form solution.

Convex Optimization

Solver LP QP SOCP SDP SOS
Gurobi
Mosek
SCS
OSQP
CSDP

Mixed-Integer Convex Optimization

Solver MILP MIQP MISOCP MISDP
Gurobi
Mosek

Nonconvex Programming

Solver Nonlinear Program LCP SMT
† ‡ SNOPT
Ipopt
NLopt
Moby LCP
dReal

† indicates that this is a commercial solver which requires a license (note that some have free licenses for academics).

‡ Note that Drake's pre-compiled binary releases provide SNOPT.

Classes

class  MathematicalProgram
 MathematicalProgram stores the decision variables, the constraints and costs of an optimization problem. More...