qp_solver_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_QP_SOLVER_INTERFACE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_QP_SOLVER_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
29 #include <corbo-core/types.h>
32 
33 #ifdef MESSAGE_SUPPORT
34 #include <corbo-communication/messages/optimization/qp_solvers.pb.h>
35 #endif
36 
37 #include <memory>
38 
39 namespace corbo {
40 
73 class QpSolverInterface
74 {
75  public:
76  using Ptr = std::shared_ptr<QpSolverInterface>;
77  using UPtr = std::unique_ptr<QpSolverInterface>;
78 
80 
82  virtual ~QpSolverInterface() = default;
83 
85  virtual Ptr getInstance() const = 0;
86 
87  virtual bool isSupportingSimpleBounds() = 0;
88 
93  virtual bool initialize() { return true; }
94 
111  bool new_structure = true, bool zero_x_warmstart = false) = 0;
112 
126  Eigen::Ref<Eigen::VectorXd> ubA, bool new_structure = true, bool zero_x_warmstart = false, bool update_P = true,
127  bool update_q = true, bool update_A = true, bool update_bounds = true) = 0;
128 
131 
134 
135  virtual void enforceNewStructure(bool new_structure = true) = 0;
136 
138  virtual void clear() = 0;
139 
140 #ifdef MESSAGE_SUPPORT
141  // implement for import / export support
142  virtual void toMessage(corbo::messages::QpSolver& message) const {}
143  virtual void fromMessage(const corbo::messages::QpSolver& message, std::stringstream* issues = nullptr) {}
144 #endif
145 };
146 
147 using QpSolverFactory = Factory<QpSolverInterface>;
148 #define FACTORY_REGISTER_QP_SOLVER(type) FACTORY_REGISTER_OBJECT(type, QpSolverInterface)
149 
150 } // namespace corbo
151 
152 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_QP_SOLVER_INTERFACE_H_
Eigen::SparseMatrix
A versatible sparse matrix representation.
Definition: SparseMatrix.h:96
factory.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::QpSolverInterface::UPtr
std::unique_ptr< QpSolverInterface > UPtr
Definition: qp_solver_interface.h:121
corbo::QpSolverInterface::isSupportingSimpleBounds
virtual bool isSupportingSimpleBounds()=0
corbo::QpSolverInterface::enforceNewStructure
virtual void enforceNewStructure(bool new_structure=true)=0
types.h
corbo::QpSolverInterface::getDualSolution
virtual Eigen::Ref< Eigen::VectorXd > getDualSolution()=0
corbo::SolverStatus
SolverStatus
Definition: optimization/include/corbo-optimization/types.h:52
corbo::QpSolverFactory
Factory< QpSolverInterface > QpSolverFactory
Definition: qp_solver_interface.h:169
corbo::QpSolverInterface::Ptr
std::shared_ptr< QpSolverInterface > Ptr
Definition: qp_solver_interface.h:120
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1520
corbo::QpSolverInterface::SparseMatrix
Eigen::SparseMatrix< double, Eigen::ColMajor, long long > SparseMatrix
Definition: qp_solver_interface.h:123
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::QpSolverInterface::updateDualSolutionWarmStart
virtual void updateDualSolutionWarmStart(const Eigen::Ref< const Eigen::VectorXd > &y)=0
corbo::QpSolverInterface::solve
virtual SolverStatus solve(SparseMatrix &P, Eigen::Ref< Eigen::VectorXd > q, SparseMatrix &A, Eigen::Ref< Eigen::VectorXd > lbA, Eigen::Ref< Eigen::VectorXd > ubA, Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub, bool new_structure=true, bool zero_x_warmstart=false)=0
Solve full QP.
corbo::QpSolverInterface::clear
virtual void clear()=0
clear internal caches
y
Scalar * y
Definition: level1_cplx_impl.h:102
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
types.h
corbo::QpSolverInterface::~QpSolverInterface
virtual ~QpSolverInterface()=default
Virtual destructor.
A
MatrixType A(a, *n, *n, *lda)
corbo::QpSolverInterface::initialize
virtual bool initialize()
Initialize the qp solver.
Definition: qp_solver_interface.h:137
corbo::QpSolverInterface::updatePrimalSolutionWarmStart
virtual void updatePrimalSolutionWarmStart(const Eigen::Ref< const Eigen::VectorXd > &x)=0
corbo::QpSolverInterface::getPrimalSolution
virtual Eigen::Ref< Eigen::VectorXd > getPrimalSolution()=0
optimization_problem_interface.h
corbo::QpSolverInterface::getInstance
virtual Ptr getInstance() const =0
Return a newly created instance of the current solver.


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:06:08