proxsuite 0.6.7
The Advanced Proximal Optimization Toolbox
|
ProxSuite is a library which provides efficient solvers for solving constrained programs encountered in robotics using dedicated proximal point based algorithms. ProxSuite is open-source, written in C++ with Python bindings, and distributed under the BSD2 licence. Contributions are welcome.
For the moment, the library offers ProxQP solver, which is a C++ implementation of the ProxQP algorithm for solving convex QPs. It is planned to release soon an extension for dealing with non linear inequality constraints as well.
In this doc, you will find the usual description of the library functionalities and a quick tutorial with examples on how to use the API.
The full installation procedure can be found here.
If you just need the Python bindings, you can directly have access to them through Conda. On systems for which binaries are not provided, installation from source should be straightforward. Every release is validated in main Linux, Mac OS X and Windows distributions.
We start with a simple program to load ProxQP and use ProxQP solver in order to solve a random generated QP problem. It is given in both C++ and Python cases.
examples/cpp/overview-simple.cpp | examples/python/overview-simple.py |
---|---|
#include <iostream>
#include <proxsuite/proxqp/dense/dense.hpp>
#include <proxsuite/proxqp/utils/random_qp_problems.hpp> // used for generating a random convex qp
using namespace proxsuite::proxqp;
using T = double;
int
main()
{
// generate a QP problem
T sparsity_factor = 0.15;
dense::isize dim = 10;
dense::isize n_eq(dim / 4);
dense::isize n_in(dim / 4);
T strong_convexity_factor(1.e-2);
// we generate a qp, so the function used from helpers.hpp is
// in proxqp namespace. The qp is in dense eigen format and
// you can control its sparsity ratio and strong convexity factor.
dense::Model<T> qp_random = utils::dense_strongly_convex_qp(
dim, n_eq, n_in, sparsity_factor, strong_convexity_factor);
// load PROXQP solver with dense backend and solve the problem
dense::QP<T> qp(dim, n_eq, n_in);
qp.init(qp_random.H,
qp_random.g,
qp_random.A,
qp_random.b,
qp_random.C,
qp_random.l,
qp_random.u);
qp.solve();
// print an optimal solution x,y and z
std::cout << "optimal x: " << qp.results.x << std::endl;
std::cout << "optimal y: " << qp.results.y << std::endl;
std::cout << "optimal z: " << qp.results.z << std::endl;
}
Definition backward_data.hpp:16 This class stores the model of the QP problem. Definition model.hpp:24 Definition wrapper.hpp:116 | import proxsuite
import numpy as np
import scipy.sparse as spa
from util import generate_mixed_qp
# generate a qp problem
n = 10
H, g, A, b, C, u, l = generate_mixed_qp(n)
n_eq = A.shape[0]
n_in = C.shape[0]
# solve it
qp = proxsuite.proxqp.dense.QP(n, n_eq, n_in)
qp.init(H, g, A, b, C, l, u)
qp.solve()
# print an optimal solution
print("optimal x: {}".format(qp.results.x))
print("optimal y: {}".format(qp.results.y))
print("optimal z: {}".format(qp.results.z))
|
You can compile the C++ version by including ProxSuite and Eigen header directories
If you are looking for the fastest performance, use the following flags to use SIMDE in proxsuite and tell your compiler to use the corresponding cpu instruction set
Once your code is compiled, you might then run it using
In Python, just run it:
This program generates a random convex QP problem and loads ProxQP solver with dense backend for solving it.
We first include the proper files. In C++, we have to include the dense backend API imported from "dense.hpp" file, and a header file "util.hpp" for generating a random QP problem (from test directory as it is used for unit testing the solver). In Python, the library is included by just importing proxsuite_pywrap, and we propose a little function generated_mixed_qp
for generating convex QP with equality and inequality constraints.
The first paragraph generates the QP problem. In the second paragraph, we first define the object Qp
, using the dimensions of the problem (i.e., n
is the dimension of primal variable x
, n_eq
the number of equality constraints, and n_in
the number of inequality constraints). We then define some settings for the solver: the accuracy threshold is set to 1.E-9, and the verbose option is set to false (so no intermediary printings will be displayed). The solver is initialized with the previously generated QP problem with the method init
. Finally, we call the solve
method. All the results are stored in Qp.results
.
ProxSuite is written in C++, with a full template-based C++ API, for efficiency purposes. All the functionalities are available in C++. Extension of the library should be preferably in C++.
However, C++ efficiency comes with a higher work cost, especially for newcomers. For this reason, all the interface is exposed in Python. We tried to build the Python API as much as possible as a mirror of the C++ interface. The greatest difference is that the C++ interface is proposed using Eigen objects for matrices and vectors, that are exposed as NumPy matrices in Python.
Happy with ProxSuite? Please cite us with the following format.
The paper is publicly available in HAL (ref 03683733).
This documentation is mostly composed of several examples, along with a technical documentation. In the next sections you will find illustrated with examples in C++ and python, (i) ProxQP API methods (with dense and sparse backends) ; the lists of solver's settings and results subclasses ; some recommandation about which backend using according to your needs ; some important remarks about timings (and compilation options for speeding up ProxQP considering your OS architecture); and finally (ii) some examples for using ProxQP without passing by the API (but only through a unique solve function).
The last parts of the documentation describes the differents namespaces, classes and files of the C++ project.