{ "cells": [ { "cell_type": "markdown", "metadata": {}, "source": [ "# MathematicalProgram Tutorial\n", "\n", "For instructions on how to run these tutorial notebooks, please see the [README](https://github.com/RobotLocomotion/drake/blob/master/tutorials/README.md)." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Background\n", "Many engineering problems can be formulated as mathematical optimization problems, and solved by numerical solvers. A generic mathematical optimization problem can be formulated as\n", "\\begin{align}\n", "\\begin{array}{rl}\n", " \\min_x \\; & f(x)\n", " \\\\[0.1pc]\\text{subject to} \\; & x \\in\\mathcal{S}\n", " \\end{array}\n", " \\hspace{1.45em}\n", " {\\scriptsize\n", " \\begin{array}{|ll|}\n", " \\hline \\text{The real-valued decision variable is} & x\n", " \\\\[-0.21pc] \\text{The real-valued cost function is} & f(x)\n", " \\\\[-0.21pc] \\text{The constraint set is} & \\mathcal{S}\n", " \\\\[-0.21pc] \\text{The optimal $x$ that minimizes the cost function is} & x^*\n", " \\\\[0.03pc]\\hline\n", " \\end{array}\n", " }\n", "\\end{align}\n", "\n", "where $x$ is the real-valued decision variable(s), $f(x)$ is the real-valued *cost function*, $\\mathcal{S}$ is the constraint set for $x$. Our goal is to find the optimal $x^*$ within the constraint set $\\mathcal{S}$, such that $x^*$ minimizes the cost function $f(x)$.\n", "\n", "For example, the following optimization problem determines the value of $x$ \n", "that minimizes $x^3 + 2x + 1$ subject to $x \\ge 1$.\n", "\\begin{align}\n", "\\begin{array}{rl}\n", " \\min_x & x^3 + 2x + 1\n", " \\\\[0.1pc] \\text{subject to} & x \\ge 1\n", "\\end{array}\n", "\\hspace{1.45em}\n", "{\\scriptsize\n", "\\begin{array}{|ll|}\n", " \\hline \\text{The real-valued decision variable is} & x\n", " \\\\[-0.21pc] \\text{The real-valued cost function $f(x)$ is} & x^3 + 2x + 1\n", " \\\\[-0.21pc] \\text{The set $\\mathcal{S}$ of constraints is} & x \\ge 1\n", " \\\\[-0.21pc] \\text{The value that minimizes the cost function is} & x^* = 1\n", " \\\\[0.03pc]\\hline\n", "\\end{array}}\n", "\\end{align}\n", "\n", "In general, how an optimization problem is solved depends on its categorization (categories include Linear Programming, Quadratic Programming, Mixed-integer Programming, etc.). Categorization depends on properties of both the cost function $f(x)$ and the constraint set $\\mathcal{S}$. For example, if the cost function $f(x)$ is a linear function of $x$, and the constraint $\\mathcal{S}$ is a linear set $\\mathcal{S} = \\{x | Ax\\le b\\}$, then we have a *linear programming* problem, which is efficiently solved with certain solvers. \n", "\n", "There are multiple solvers for each category of optimization problems,\n", "but each solver has its own API and data structures.\n", "Frequently, users need to rewrite code when they switch solvers.\n", "To remedy this, Drake provides a common API through the *MathematicalProgram* class.\n", "In addition to avoiding solver-specific code,\n", "the constraint and cost functions can be written in symbolic form (which makes code more readable).\n", "In these ways, Drake's MathematicalProgram is akin to [YALMIP](https://yalmip.github.io/) in MATLAB or [JuMP](https://github.com/JuliaOpt/JuMP.jl) in Julia, and we support both Python and C++.\n", "
Note: Drake supports many [solvers](https://drake.mit.edu/doxygen_cxx/group__solvers.html)\n", "(some are open-source and some require a license).\n", "\n", "Drake can formulate and solve the following categories of optimization problems\n", "* Linear programming\n", "* Quadratic programming\n", "* Second-order cone programming\n", "* Nonlinear nonconvex programming\n", "* Semidefinite programming\n", "* Sum-of-squares programming\n", "* Mixed-integer programming (mixed-integer linear programming, mixed-integer quadratic programming, mixed-integer second-order cone programming).\n", "* Linear complementarity problem\n", "\n", "This tutorial provides the basics of Drake's MathematicalProgram.\n", "Advanced tutorials are available at the [bottom](#Advanced-tutorials) of this document.\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Basics of MathematicalProgram class\n", "Drake's MathematicalProgram class contains the mathematical formulation of an optimization problem, namely the decision variables $x$, the cost function $f(x)$, and the constraint set $\\mathcal{S}$." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Initialize a MathematicalProgram object\n", "\n", " To initialize this class, first create an empty MathematicalProgram as" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "from pydrake.solvers.mathematicalprogram import MathematicalProgram\n", "import numpy as np\n", "\n", "# Create an empty MathematicalProgram named prog (with no decision variables, \n", "# constraints or cost function)\n", "prog = MathematicalProgram()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\n", "\n", "### Adding decision variables\n", "Shown below, the function `NewContinuousVariables` adds two new continuous decision variables to `prog`. The newly added variables are returned as `x` in a numpy array. \n", "
Note the range of the variable is a continuous set, as opposed to binary variables which only take discrete value 0 or 1." ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "x = prog.NewContinuousVariables(2)\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The default names of the variable in *x* are \"x(0)\" and \"x(1)\". The next line prints the default names and types in `x`, whereas the second line prints the symbolic expression \"1 + 2x[0] + 3x[1] + 4x[1]\"." ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "print(x)\n", "print(1 + 2*x[0] + 3*x[1] + 4*x[1])" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "To create an array `y` of two variables named \"dog(0)\"\" and \"dog(1)\", pass the name \"dog\" as a second argument to `NewContinuousVariables()`. Also shown below is the printout of the two variables in `y` and a symbolic expression involving `y`." ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "y = prog.NewContinuousVariables(2, \"dog\")\n", "print(y)\n", "print(y[0] + y[0] + y[1] * y[1] * y[1])" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "To create a $3 \\times 2$ matrix of variables named \"A\", type " ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "var_matrix = prog.NewContinuousVariables(3, 2, \"A\")\n", "print(var_matrix)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Adding constraints\n", "There are many ways to impose constraints on the decision variables. This tutorial shows a few simple examples. Refer to the links at the [bottom](#Advanced-tutorials) of this document for other types of constraints.\n", "\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### AddConstraint\n", "The simplest way to add a constraint is with `MathematicalProgram.AddConstraint()`." ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "# Add the constraint x(0) * x(1) = 1 to prog\n", "prog.AddConstraint(x[0] * x[1] == 1)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\n", "You can also add inequality constraints to `prog` such as" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "prog.AddConstraint(x[0] >= 0)\n", "prog.AddConstraint(x[0] - x[1] <= 0)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "`prog` automatically analyzes these symbolic inequality constraint expressions and determines they are all *linear* constraints on $x$." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Adding Cost functions\n", "In a complicated optimization problem, it is often convenient to write the total cost function $f(x)$ as a sum of individual cost functions\n", "\\begin{align}\n", "f(x) = \\sum_i g_i(x)\n", "\\end{align}" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "\n", "#### AddCost method.\n", "The simplest way to add an individual cost function $g_i(x)$ to the total cost function $f(x)$ is with the `MathematicalProgram.AddCost()` method (as shown below)." ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "# Add a cost x(0)**2 + 3 to the total cost. Since prog doesn't have a cost before, now the total cost is x(0)**2 + 3\n", "prog.AddCost(x[0] ** 2 + 3)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "To add another individual cost function $x(0) + x(1)$ to the total cost function $f(x)$, simply call `AddCost()` again as follows" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "prog.AddCost(x[0] + x[1])" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "now the total cost function becomes $x(0)^2 + x(0) + x(1) + 3$.\n", "\n", "`prog` can analyze each of these individual cost functions and determine that $x(0) ^ 2 + 3$ is a convex quadratic function, and $x(0) + x(1)$ is a linear function of $x$." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Solve the optimization problem\n", "Once all the decision variables/constraints/costs are added to `prog`, we are ready to solve the optimization problem.\n", "\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### Automatically choosing a solver\n", "The simplest way to solve the optimization problem is to call `Solve()` function. Drake's MathematicalProgram analyzes the type of the constraints/costs, and then calls an appropriate solver for your problem. The result of calling `Solve()` is stored inside the return argument. Here is a code snippet" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "\"\"\"\n", "Solves a simple optimization problem\n", " min x(0)^2 + x(1)^2\n", "subject to x(0) + x(1) = 1\n", " x(0) <= x(1)\n", "\"\"\"\n", "from pydrake.solvers.mathematicalprogram import Solve\n", "# Set up the optimization problem.\n", "prog = MathematicalProgram()\n", "x = prog.NewContinuousVariables(2)\n", "prog.AddConstraint(x[0] + x[1] == 1)\n", "prog.AddConstraint(x[0] <= x[1])\n", "prog.AddCost(x[0] **2 + x[1] ** 2)\n", "\n", "# Now solve the optimization problem.\n", "result = Solve(prog)\n", "\n", "# print out the result.\n", "print(\"Success? \", result.is_success())\n", "# Print the solution to the decision variables.\n", "print('x* = ', result.GetSolution(x))\n", "# Print the optimal cost.\n", "print('optimal cost = ', result.get_optimal_cost())\n", "# Print the name of the solver that was called.\n", "print('solver is: ', result.get_solver_id().name())" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Notice that we can then retrieve optimization result from the return argument of `Solve`. For example, the solution $x^*$ is retrieved from `result.GetSolution()`, and the optimal cost from `result.get_optimal_cost()`.\n", "\n", "Some optimization solution is infeasible (doesn't have a solution). For example in the following code example, `result.get_solution_result()` will not report `kSolutionFound`." ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "\"\"\"\n", "An infeasible optimization problem.\n", "\"\"\"\n", "prog = MathematicalProgram()\n", "x = prog.NewContinuousVariables(1)[0]\n", "y = prog.NewContinuousVariables(1)[0]\n", "prog.AddConstraint(x + y >= 1)\n", "prog.AddConstraint(x + y <= 0)\n", "prog.AddCost(x)\n", "\n", "result = Solve(prog)\n", "print(\"Success? \", result.is_success())\n", "print(result.get_solution_result())" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "#### Manually choosing a solver\n", "\n", "If you want to choose a solver yourself, rather than Drake choosing one for you, you could instantiate a solver explicitly, and call its `Solve` function. For example, if I want to solve a problem using the open-source solver [IPOPT](https://github.com/coin-or/Ipopt), here is a code snippet" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "\"\"\"\n", "Demo on manually choosing a solver\n", "Solves the problem\n", "min x(0)\n", "s.t x(0) + x(1) = 1\n", " 0 <= x(1) <= 1\n", "\"\"\"\n", "from pydrake.solvers.ipopt import IpoptSolver\n", "prog = MathematicalProgram()\n", "x = prog.NewContinuousVariables(2)\n", "prog.AddConstraint(x[0] + x[1] == 1)\n", "prog.AddConstraint(0 <= x[1])\n", "prog.AddConstraint(x[1] <= 1)\n", "prog.AddCost(x[0])\n", "\n", "# Choose IPOPT as the solver.\n", "# First instantiate an IPOPT solver.\n", "\n", "solver = IpoptSolver()\n", "# The initial guess is [1, 1]. The third argument is the options for Ipopt solver,\n", "# and we set no solver options.\n", "result = solver.Solve(prog, np.array([1, 1]), None)\n", "\n", "print(result.get_solution_result())\n", "print(\"x* = \", result.GetSolution(x))\n", "print(\"Solver is \", result.get_solver_id().name())\n", "print(\"Ipopt solver status: \", result.get_solver_details().status,\n", " \", meaning \", result.get_solver_details().ConvertStatusToString())\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Note that `solver.Solve()` expects three input arguments, the optimization program `prog`, the initial guess of the decision variable values (`[1, 1]` in this case), and an optional setting for the solver (`None` in this case, we use the default IPOPT setting). If you don't have an initial guess, you can substitute `np.array([1, 1])` with `None`. The solver will choose an initial guess automatically, as shown in the code below" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "result = solver.Solve(prog, None, None)\n", "print(result.get_solution_result())\n", "print(\"x* = \", result.GetSolution(x))" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Also note that if we know which solver is called, then we can access some solver-specific result, by calling `result.get_solver_details()`. For example, `IpoptSolverDetails` contains a field `status`, namely the status code of the IPOPT solver, we could access this info by" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [ "print(\"Ipopt solver status: \", result.get_solver_details().status,\n", " \", meaning \", result.get_solver_details().ConvertStatusToString())" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Each solver has its own details. You should refer to `XXXSolverDetails` class on what is stored inside the return argument of `result.get_solver_details()`. For example, if you know that IPOPT is called, then refer to `IpoptSolverDetails` class; for OSQP solver, refer to `OsqpSolverDetails`, etc." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Advanced tutorials\n", "[Setting solver parameters](./solver_parameters.ipynb)\n", "\n", "[Linear program](./linear_program.ipynb)\n", "\n", "[Sum-of-squares optimization](./sum_of_squares_optimization.ipynb)" ] } ], "metadata": { "colab": { "collapsed_sections": [], "name": "MathematicalProgram tutorial.ipynb", "provenance": [], "version": "0.3.2" }, "kernelspec": { "display_name": "Python 3", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.6.9" } }, "nbformat": 4, "nbformat_minor": 1 }