|
| 1 | +// Copyright 2023 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ |
| 16 | +#define AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ |
| 17 | + |
| 18 | +#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" |
| 19 | +#include "autoware/qp_interface/qp_interface.hpp" |
| 20 | +#include "osqp/osqp.h" |
| 21 | + |
| 22 | +#include <limits> |
| 23 | +#include <memory> |
| 24 | +#include <string> |
| 25 | +#include <vector> |
| 26 | + |
| 27 | +namespace autoware::qp_interface |
| 28 | +{ |
| 29 | +constexpr c_float OSQP_INF = 1e30; |
| 30 | + |
| 31 | +class OSQPInterface : public QPInterface |
| 32 | +{ |
| 33 | +public: |
| 34 | + /// \brief Constructor without problem formulation |
| 35 | + OSQPInterface( |
| 36 | + const bool enable_warm_start = false, const int max_iteration = 20000, |
| 37 | + const c_float eps_abs = std::numeric_limits<c_float>::epsilon(), |
| 38 | + const c_float eps_rel = std::numeric_limits<c_float>::epsilon(), const bool polish = true, |
| 39 | + const bool verbose = false); |
| 40 | + /// \brief Constructor with problem setup |
| 41 | + /// \param P: (n,n) matrix defining relations between parameters. |
| 42 | + /// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound. |
| 43 | + /// \param q: (n) vector defining the linear cost of the problem. |
| 44 | + /// \param l: (m) vector defining the lower bound problem constraint. |
| 45 | + /// \param u: (m) vector defining the upper bound problem constraint. |
| 46 | + /// \param eps_abs: Absolute convergence tolerance. |
| 47 | + OSQPInterface( |
| 48 | + const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q, |
| 49 | + const std::vector<double> & l, const std::vector<double> & u, |
| 50 | + const bool enable_warm_start = false, |
| 51 | + const c_float eps_abs = std::numeric_limits<c_float>::epsilon()); |
| 52 | + OSQPInterface( |
| 53 | + const CSC_Matrix & P, const CSC_Matrix & A, const std::vector<double> & q, |
| 54 | + const std::vector<double> & l, const std::vector<double> & u, |
| 55 | + const bool enable_warm_start = false, |
| 56 | + const c_float eps_abs = std::numeric_limits<c_float>::epsilon()); |
| 57 | + ~OSQPInterface(); |
| 58 | + |
| 59 | + static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept; |
| 60 | + |
| 61 | + std::vector<double> optimize( |
| 62 | + CSC_Matrix P, CSC_Matrix A, const std::vector<double> & q, const std::vector<double> & l, |
| 63 | + const std::vector<double> & u); |
| 64 | + |
| 65 | + int getIterationNumber() const override; |
| 66 | + bool isSolved() const override; |
| 67 | + std::string getStatus() const override; |
| 68 | + |
| 69 | + int getPolishStatus() const; |
| 70 | + std::vector<double> getDualSolution() const; |
| 71 | + |
| 72 | + void updateEpsAbs(const double eps_abs) override; |
| 73 | + void updateEpsRel(const double eps_rel) override; |
| 74 | + void updateVerbose(const bool verbose) override; |
| 75 | + |
| 76 | + // Updates problem parameters while keeping solution in memory. |
| 77 | + // |
| 78 | + // Args: |
| 79 | + // P_new: (n,n) matrix defining relations between parameters. |
| 80 | + // A_new: (m,n) matrix defining parameter constraints relative to the lower and upper bound. |
| 81 | + // q_new: (n) vector defining the linear cost of the problem. |
| 82 | + // l_new: (m) vector defining the lower bound problem constraint. |
| 83 | + // u_new: (m) vector defining the upper bound problem constraint. |
| 84 | + void updateP(const Eigen::MatrixXd & P_new); |
| 85 | + void updateCscP(const CSC_Matrix & P_csc); |
| 86 | + void updateA(const Eigen::MatrixXd & A_new); |
| 87 | + void updateCscA(const CSC_Matrix & A_csc); |
| 88 | + void updateQ(const std::vector<double> & q_new); |
| 89 | + void updateL(const std::vector<double> & l_new); |
| 90 | + void updateU(const std::vector<double> & u_new); |
| 91 | + void updateBounds(const std::vector<double> & l_new, const std::vector<double> & u_new); |
| 92 | + |
| 93 | + void updateMaxIter(const int iter); |
| 94 | + void updateRhoInterval(const int rho_interval); |
| 95 | + void updateRho(const double rho); |
| 96 | + void updateAlpha(const double alpha); |
| 97 | + void updateScaling(const int scaling); |
| 98 | + void updatePolish(const bool polish); |
| 99 | + void updatePolishRefinementIteration(const int polish_refine_iter); |
| 100 | + void updateCheckTermination(const int check_termination); |
| 101 | + |
| 102 | + /// \brief Get the number of iteration taken to solve the problem |
| 103 | + inline int64_t getTakenIter() const { return static_cast<int64_t>(latest_work_info_.iter); } |
| 104 | + /// \brief Get the status message for the latest problem solved |
| 105 | + inline std::string getStatusMessage() const |
| 106 | + { |
| 107 | + return static_cast<std::string>(latest_work_info_.status); |
| 108 | + } |
| 109 | + /// \brief Get the runtime of the latest problem solved |
| 110 | + inline double getRunTime() const { return latest_work_info_.run_time; } |
| 111 | + /// \brief Get the objective value the latest problem solved |
| 112 | + inline double getObjVal() const { return latest_work_info_.obj_val; } |
| 113 | + /// \brief Returns flag asserting interface condition (Healthy condition: 0). |
| 114 | + inline int64_t getExitFlag() const { return exitflag_; } |
| 115 | + |
| 116 | + // Setter functions for warm start |
| 117 | + bool setWarmStart( |
| 118 | + const std::vector<double> & primal_variables, const std::vector<double> & dual_variables); |
| 119 | + bool setPrimalVariables(const std::vector<double> & primal_variables); |
| 120 | + bool setDualVariables(const std::vector<double> & dual_variables); |
| 121 | + |
| 122 | +private: |
| 123 | + std::unique_ptr<OSQPWorkspace, std::function<void(OSQPWorkspace *)>> work_; |
| 124 | + std::unique_ptr<OSQPSettings> settings_; |
| 125 | + std::unique_ptr<OSQPData> data_; |
| 126 | + // store last work info since work is cleaned up at every execution to prevent memory leak. |
| 127 | + OSQPInfo latest_work_info_; |
| 128 | + // Number of parameters to optimize |
| 129 | + int64_t param_n_; |
| 130 | + // Flag to check if the current work exists |
| 131 | + bool work__initialized = false; |
| 132 | + // Exitflag |
| 133 | + int64_t exitflag_; |
| 134 | + |
| 135 | + void initializeProblemImpl( |
| 136 | + const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q, |
| 137 | + const std::vector<double> & l, const std::vector<double> & u) override; |
| 138 | + |
| 139 | + void initializeCSCProblemImpl( |
| 140 | + CSC_Matrix P, CSC_Matrix A, const std::vector<double> & q, const std::vector<double> & l, |
| 141 | + const std::vector<double> & u); |
| 142 | + |
| 143 | + std::vector<double> optimizeImpl() override; |
| 144 | +}; |
| 145 | +} // namespace autoware::qp_interface |
| 146 | + |
| 147 | +#endif // AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ |
0 commit comments