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 
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 
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_
Generic factory object.
Definition: factory.h:68
Scalar * x
Scalar * y
A versatible sparse matrix representation.
Definition: SparseMatrix.h:96
virtual void updateDualSolutionWarmStart(const Eigen::Ref< const Eigen::VectorXd > &y)=0
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.
Generic interface for QP solver implementations.
virtual void updatePrimalSolutionWarmStart(const Eigen::Ref< const Eigen::VectorXd > &x)=0
virtual void clear()=0
clear internal caches
MatrixType A(a, *n, *n, *lda)
virtual ~QpSolverInterface()=default
Virtual destructor.
virtual bool initialize()
Initialize the qp solver.
virtual Eigen::Ref< Eigen::VectorXd > getPrimalSolution()=0
EIGEN_DEVICE_FUNC const Scalar & q
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
virtual void enforceNewStructure(bool new_structure=true)=0
virtual Ptr getInstance() const =0
Return a newly created instance of the current solver.
std::shared_ptr< QpSolverInterface > Ptr
virtual bool isSupportingSimpleBounds()=0
virtual Eigen::Ref< Eigen::VectorXd > getDualSolution()=0
std::unique_ptr< QpSolverInterface > UPtr


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:07:14