Numerical optimization

Quadratic programming

Quadratic programming is a class of numerical optimization problems that can be solved efficiently. It is used for instance by the IK solver to solve whole-body control by inverse kinematics.

pymanoid.qpsolvers.solve_qp(P, q, G=None, h=None, A=None, b=None, solver='quadprog', initvals=None, sym_proj=False)

Solve a Quadratic Program defined as:

minimize

(1/2) * x.T * P * x + q.T * x

subject to

G * x <= h A * x == b

using one of the available QP solvers.

Parameters
  • P (numpy.array, scipy.sparse.csc_matrix or cvxopt.spmatrix) – Symmetric quadratic-cost matrix (most solvers require it to be definite as well).

  • q (numpy.array) – Quadratic-cost vector.

  • G (numpy.array, scipy.sparse.csc_matrix or cvxopt.spmatrix) – Linear inequality matrix.

  • h (numpy.array) – Linear inequality vector.

  • A (numpy.array, scipy.sparse.csc_matrix or cvxopt.spmatrix) – Linear equality matrix.

  • b (numpy.array) – Linear equality vector.

  • solver (string, optional) – Name of the QP solver, to choose in qpsolvers.available_solvers.

  • initvals (array, optional) – Vector of initial x values used to warm-start the solver.

  • sym_proj (bool, optional) – Set to True when the P matrix provided is not symmetric.

Returns

x – Optimal solution if found, None otherwise.

Return type

array or None

Notes

In quadratic programming, the matrix P should be symmetric. Many solvers (including CVXOPT, OSQP and quadprog) leverage this property and may return erroneous results when it is not the case. You can set sym_proj=True to project P on its symmetric part, at the cost of some computation time.

Nonlinear programming

Nonlinear programming is a catch-all expression for numerical optimization problems that don’t have any particular structure, such as convexity, allowing them to be solved more efficiently by dedicated methods. It is used for instance in nonlinear model predictive control to compute locomotion trajectories over uneven terrains.

class pymanoid.nlp.NonlinearProgram(solver='ipopt', options=None)

Wrapper around CasADi to formulate and solve nonlinear optimization problems.

Parameters
  • solver (string, optional) – Solver name. Use ‘ipopt’ (default) for an interior point method or ‘sqpmethod’ for sequential quadratic programming.

  • options (dict, optional) – Dictionary of solver options.

add_constraint(expr, lb, ub, name=None)

Add a new constraint to the problem.

Parameters
  • expr (casadi.MX) – Python or CasADi symbolic expression.

  • lb (array) – Lower-bound on the expression.

  • ub (array) – Upper-bound on the expression.

  • name (string, optional) – If provided, will stored the expression under this name for future updates.

add_equality_constraint(expr1, expr2, name=None)

Add an equality constraint between two expressions.

Parameters
  • expr1 (casadi.MX) – Expression on problem variables.

  • expr2 (casadi.MX) – Expression on problem variables.

  • name (string, optional) – If provided, will stored the expression under this name for future updates.

casadi_expand = True

Replace MX with SX expressions in problem formulation.

Note

Setting this option to True seems to significantly improve computation times when using IPOPT.

create_solver()

Create a new nonlinear solver.

extend_cost(expr)

Add a new expression term to the cost function of the problem.

Parameters

expr (casadi.MX) – Python or CasADi symbolic expression.

has_constraint(name)

Check if a given name identifies a problem constraint.

ipopt_fast_step_computation = 'yes'

If set to yes, the algorithm assumes that the linear system that is solved to obtain the search direction, is solved sufficiently well. In that case, no residuals are computed, and the computation of the search direction is a little faster.

ipopt_fixed_variable_treatment = 'relax_bounds'

Default is “make_parameter”, but “relax_bounds” seems to make computations faster and numerically stabler.

ipopt_linear_solver = 'ma27'

Linear solver used for step computations.

ipopt_max_cpu_time = 10.0

Maximum number of CPU seconds. Note that this parameter corresponds to processor time, not wall time. For a CPU with N cores, the latter can be as much as N times lower than the former.

ipopt_max_iter = 1000

Maximum number of iterations.

ipopt_mu_strategy = 'adaptive'

“monotone” (default) or “adaptive”.

Type

Update strategy for barrier parameter

ipopt_nlp_lower_bound_inf = -9000000000.0

Any bound below this value will be considered -inf, i.e. not lower bounded.

ipopt_nlp_upper_bound_inf = 9000000000.0

Any bound above this value will be considered +inf, i.e. not upper bounded.

ipopt_print_level = 0

Output verbosity level between 0 and 12.

ipopt_print_time = False

Print detailed solver computation times.

ipopt_warm_start_init_point = 'yes'

Indicates whether the optimization should use warm start initialization, where values of primal and dual variables are given (e.g. from a previous optimization of a related problem).

property iter_count

Number of LP solver iterations applied by the NLP solver.

new_constant(name, dim, value)

Add a new constant to the problem.

Parameters
  • name (string) – Name of the constant.

  • dim (int) – Number of dimensions.

  • value (array, shape=(dim,)) – Value of the constant.

Note

Constants are implemented as variables with matching lower and upper bounds.

new_variable(name, dim, init, lb, ub)

Add a new variable to the problem.

Parameters
  • name (string) – Variable name.

  • dim (int) – Number of dimensions.

  • init (array, shape=(dim,)) – Initial values.

  • lb (array, shape=(dim,)) – Vector of lower bounds on variable values.

  • ub (array, shape=(dim,)) – Vector of upper bounds on variable values.

property optimal_found

True if and only if the solution is a local optimum.

property return_status

String containing a status message from the NLP solver.

solve()

Call the nonlinear solver.

Returns

x – Vector of variable coordinates for the best solution found.

Return type

array

property solve_time

Time (in seconds) taken to solve the problem.

update_constant(name, value)

Update the value of an existing constant.

Parameters
  • name (string) – Name of the constant.

  • value (array, shape=(dim,)) – Vector of new values for the constant.

update_constraint_bounds(name, lb, ub)

Update lower- and upper-bounds on an existing constraint.

Parameters
  • name (string) – Identifier of the constraint.

  • lb (array) – New lower-bound of the constraint.

  • ub (array) – New upper-bound of the constraint.

update_variable_bounds(name, lb, ub)

Update the lower- and upper-bounds on an existing variable.

Parameters
  • name (string) – Name of the variable.

  • lb (array, shape=(dim,)) – Vector of lower bounds on variable values.

  • ub (array, shape=(dim,)) – Vector of upper bounds on variable values.

warm_start(initvals)

Warm-start the problem with a new vector of initial values.

Parameters

initvals (array) – Vector of initial values for all problem variables.