Drake
Drake C++ Documentation
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 open source and 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
CLP
CSDP
Clarabel
SCS
OSQP
SNOPT † ‡
Ipopt
NLopt

† This is a commercial solver which requires a license (note that some have free licenses for academics). See the build system documentation for details.

Drake's pre-compiled binary releases incorporate a private build of SNOPT that does not require a license when invoked via Drake's SnoptSolver wrapper class.

♦ A preferred solver for the given category.

⟡ The native CSDP solver cannot handle free variables (namely all variables have to be constrained within a cone). In Drake we apply special techniques to handle free variables (refer to RemoveFreeVariableMethod for more details). These heuristics can make the problem expensive to solve or poorly conditioned.

△ These solvers are not accurate. They implement ADMM algorithm, which converges quickly to a low-accuracy solution, and requires many iterations to achieve high accuracy.

▢ These solvers can solve the convex problems, but are not good at it. They treat the convex problems as general nonlinear optimization problems.

⬘ These gradient-based solvers expect smooth gradients. These problems don't have smooth gradients everywhere, hence even though the problem is convex, these gradient-bases solvers might not converge to the globally optimal solution.

Mixed-Integer Convex Optimization

Solver MILP MIQP MISOCP MISDP
Gurobi
MOSEK
naive branch-and-bound

† This is a commercial solver which requires a license (note that some have free licenses for academics). See the build system documentation for details.

♦ A preferred solver for the given category.

◊ The naive solver's usefulness is likely restricted to small-sized problems with dozens of binary variables. We implement only the basic branch-and-bound algorithm, without cutting planes nor advanced branching heuristics.

Nonconvex Programming

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

† This is a commercial solver which requires a license (note that some have free licenses for academics). See the build system documentation for details.

Drake's pre-compiled binary releases incorporate a private build of SNOPT that does not require a license when invoked via Drake's SnoptSolver wrapper class.

♦ A preferred solver for the given category. ⟐ SNOPT/IPOPT/NLOPT might be able to solve LCP, but they are not the preferred solver.

Modules

 Costs and Constraints
 Most simple costs and constraints can be added directly to a MathematicalProgram through the MathematicalProgram::AddCost() and MathematicalProgram::AddConstraint() interfaces and their specializations.
 
 Geometry Optimization
 Provides an abstraction for reasoning about geometry in optimization problems, and using optimization problems to solve geometry problems.
 

Classes

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