Template Struct QP
Defined in File wrapper.hpp
Struct Documentation
-
template<typename T, typename I>
struct QP This class defines the API of PROXQP solver with sparse backend.
Wrapper class for using proxsuite API with dense backend for solving linearly constrained convex QP problem using ProxQp algorithm.
Example usage:
#include <Eigen/Core> #include <Eigen/Cholesky> #include <proxsuite/proxqp/dense/dense.hpp> #include <proxsuite/linalg/veg/util/dbg.hpp> #include <util.hpp> using T = double; using I = c_int; auto main() -> int { // Generate a random QP problem with primal variable dimension of size dim; n_eq equality constraints and n_in inequality constraints ::proxsuite::proxqp::test::rand::set_seed(1); proxqp::isize dim = 10; proxqp::isize n_eq(dim / 4); proxqp::isize n_in(dim / 4); T strong_convexity_factor(1.e-2); T sparsity_factor = 0.15; // controls the sparsity of each matrix of the problem generated T eps_abs = T(1e-9); double p = 1.0; T conditioning(10.0); auto H = ::proxsuite::proxqp::test::rand::sparse_positive_definite_rand(n, conditioning, p); auto g = ::proxsuite::proxqp::test::rand::vector_rand<T>(n); auto A = ::proxsuite::proxqp::test::rand::sparse_matrix_rand<T>(n_eq,n, p); auto b = ::proxsuite::proxqp::test::rand::vector_rand<T>(n_eq); auto C = ::proxsuite::proxqp::test::rand::sparse_matrix_rand<T>(n_in,n, p); auto l = ::proxsuite::proxqp::test::rand::vector_rand<T>(n_in); auto u = (l.array() + 1).matrix().eval(); proxqp::sparse::QP<T,I> Qp(n, n_eq, n_in); Qp.settings.eps_abs = 1.E-9; Qp.settings.verbose = true; Qp.setup_sparse_matrices(H,g,A,b,C,u,l); Qp.solve(); // Solve the problem proxqp::sparse::QP<T,I> Qp(n, n_eq, n_in); Qp.settings.eps_abs = 1.E-9; Qp.settings.verbose = true; Qp.setup_sparse_matrices(H,g,A,b,C,u,l); Qp.solve(); // Verify solution accuracy T pri_res = std::max( (qp.A * Qp.results.x - qp.b).lpNorm<Eigen::Infinity>(), (helpers::positive_part(qp.C * Qp.results.x - qp.u) + helpers::negative_part(qp.C * Qp.results.x - qp.l)) .lpNorm<Eigen::Infinity>()); T dua_res = (qp.H * Qp.results.x + qp.g + qp.A.transpose() * Qp.results.y + qp.C.transpose() * Qp.results.z) .lpNorm<Eigen::Infinity>(); VEG_ASSERT(pri_res <= eps_abs); VEG_ASSERT(dua_res <= eps_abs); // Some solver statistics std::cout << "------solving qp with dim: " << dim << " neq: " << n_eq << " nin: " << n_in << std::endl; std::cout << "primal residual: " << pri_res << std::endl; std::cout << "dual residual: " << dua_res << std::endl; std::cout << "total number of iteration: " << Qp.results.info.iter << std::endl; }
Public Functions
-
inline QP(isize dim, isize n_eq, isize n_in)
Default constructor using the dimension of the matrices in entry.
- Parameters:
dim – primal variable dimension.
n_eq – number of equality constraints.
n_in – number of inequality constraints.
-
inline QP(const SparseMat<bool, I> &H, const SparseMat<bool, I> &A, const SparseMat<bool, I> &C)
Default constructor using the sparsity structure of the matrices in entry.
-
inline void init(optional<SparseMat<T, I>> H, optional<VecRef<T>> g, optional<SparseMat<T, I>> A, optional<VecRef<T>> b, optional<SparseMat<T, I>> C, optional<VecRef<T>> l, optional<VecRef<T>> u, bool compute_preconditioner_ = true, optional<T> rho = nullopt, optional<T> mu_eq = nullopt, optional<T> mu_in = nullopt, optional<T> manual_minimal_H_eigenvalue = nullopt)
Setups the QP model (with sparse matrix format) and equilibrates it.
- Parameters:
H – quadratic cost input defining the QP model.
g – linear cost input defining the QP model.
A – equality constraint matrix input defining the QP model.
b – equality constraint vector input defining the QP model.
C – inequality constraint matrix input defining the QP model.
l – lower inequality constraint vector input defining the QP model.
u – upper inequality constraint vector input defining the QP model.
compute_preconditioner – boolean parameter for executing or not the preconditioner.
rho – proximal step size wrt primal variable.
mu_eq – proximal step size wrt equality constrained multiplier.
mu_in – proximal step size wrt inequality constrained multiplier.
-
inline void update(const optional<SparseMat<T, I>> H, optional<VecRef<T>> g, const optional<SparseMat<T, I>> A, optional<VecRef<T>> b, const optional<SparseMat<T, I>> C, optional<VecRef<T>> l, optional<VecRef<T>> u, bool update_preconditioner = false, optional<T> rho = nullopt, optional<T> mu_eq = nullopt, optional<T> mu_in = nullopt, optional<T> manual_minimal_H_eigenvalue = nullopt)
Updates the QP model (with sparse matrix format) and re-equilibrates it if specified by the user. If matrices in entry are not null, the update is effective only if the sparsity structure of entry is the same as the one used for the initialization.
Note
The init method should be called before update. If it has not been done before, init is called depending on the is_initialized flag.
- Parameters:
H – quadratic cost input defining the QP model.
g – linear cost input defining the QP model.
A – equality constraint matrix input defining the QP model.
b – equality constraint vector input defining the QP model.
C – inequality constraint matrix input defining the QP model.
l – lower inequality constraint vector input defining the QP model.
u – lower inequality constraint vector input defining the QP model.
update_preconditioner – bool parameter for updating or not the preconditioner and the associated scaled model.
rho – proximal step size wrt primal variable.
mu_eq – proximal step size wrt equality constrained multiplier.
mu_in – proximal step size wrt inequality constrained multiplier.
-
inline void solve(optional<VecRef<T>> x, optional<VecRef<T>> y, optional<VecRef<T>> z)
Solves the QP problem using PROXQP algorithm and a warm start.
- Parameters:
x – primal warm start.
y – dual equality warm start.
z – dual inequality warm start.
-
inline void cleanup()
Clean-ups solver’s results.
-
inline QP(isize dim, isize n_eq, isize n_in)