wbc
OsqpSolver.hpp
Go to the documentation of this file.
1#ifndef WBC_OSQP_SOLVER_HPP
2#define WBC_OSQP_SOLVER_HPP
3
4#include <Eigen/Sparse>
5#include <OsqpEigen/Solver.hpp>
8
9namespace wbc {
10
31class OsqpSolver : public QPSolver{
32private:
34public:
35 OsqpSolver();
37
43 virtual void solve(const HierarchicalQP& hierarchical_qp, Eigen::VectorXd& solver_output, bool allow_warm_start = true);
44
46 OsqpEigen::Solver solver;
47
48protected:
50
51 Eigen::MatrixXd hessian_dense;
52 Eigen::SparseMatrix<double> hessian_sparse;
53 Eigen::MatrixXd constraint_mat_dense;
54 Eigen::SparseMatrix<double> constraint_mat_sparse;
55 Eigen::VectorXd gradient;
56 Eigen::VectorXd lower_bound;
57 Eigen::VectorXd upper_bound;
58
59 void resize(uint nq, uint nc);
60 std::string exitFlagToString(OsqpEigen::ErrorExitFlag flag){
61 switch(flag){
62 case OsqpEigen::ErrorExitFlag::DataValidationError: return "DataValidationError";
63 case OsqpEigen::ErrorExitFlag::SettingsValidationError: return "SettingsValidationError";
64 case OsqpEigen::ErrorExitFlag::LinsysSolverLoadError: return "LinsysSolverLoadError";
65 case OsqpEigen::ErrorExitFlag::LinsysSolverInitError: return "LinsysSolverInitError";
66 case OsqpEigen::ErrorExitFlag::NonCvxError: return "NonCvxError";
67 case OsqpEigen::ErrorExitFlag::MemAllocError: return "MemAllocError";
68 case OsqpEigen::ErrorExitFlag::WorkspaceNotInitError: return "WorkspaceNotInitError";
69 default: return "NoError";
70 }
71 }
72};
73
74}
75
76#endif
OsqpSolver()
Definition OsqpSolver.cpp:9
Eigen::VectorXd upper_bound
Definition OsqpSolver.hpp:57
std::string exitFlagToString(OsqpEigen::ErrorExitFlag flag)
Definition OsqpSolver.hpp:60
void resize(uint nq, uint nc)
Definition OsqpSolver.cpp:15
Eigen::MatrixXd constraint_mat_dense
Definition OsqpSolver.hpp:53
Eigen::VectorXd gradient
Definition OsqpSolver.hpp:55
Eigen::MatrixXd hessian_dense
Definition OsqpSolver.hpp:51
OsqpEigen::Solver solver
Definition OsqpSolver.hpp:46
~OsqpSolver()
Definition OsqpSolver.cpp:12
virtual void solve(const HierarchicalQP &hierarchical_qp, Eigen::VectorXd &solver_output, bool allow_warm_start=true)
solve Solve the given quadratic program
Definition OsqpSolver.cpp:44
Eigen::SparseMatrix< double > hessian_sparse
Definition OsqpSolver.hpp:52
bool configured
Definition OsqpSolver.hpp:49
Eigen::SparseMatrix< double > constraint_mat_sparse
Definition OsqpSolver.hpp:54
Eigen::VectorXd lower_bound
Definition OsqpSolver.hpp:56
QPSolver()
Definition QPSolver.cpp:5
Definition ContactsAccelerationConstraint.cpp:3
Describes a hierarchy of quadratic programs.
Definition QuadraticProgram.hpp:53
Definition QPSolver.hpp:69