24
24
#include < string>
25
25
#include < vector>
26
26
27
- namespace qp
27
+ namespace autoware ::common
28
28
{
29
- constexpr c_float INF = 1e30 ;
29
+ constexpr c_float OSQP_INF = 1e30 ;
30
30
31
31
class OSQPInterface : public QPInterface
32
32
{
33
33
public:
34
34
// / \brief Constructor without problem formulation
35
35
OSQPInterface (
36
36
const bool enable_warm_start = false ,
37
- const c_float eps_abs = std::numeric_limits<c_float>::epsilon(), const bool polish = true );
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 );
38
40
// / \brief Constructor with problem setup
39
41
// / \param P: (n,n) matrix defining relations between parameters.
40
42
// / \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound.
@@ -60,8 +62,10 @@ class OSQPInterface : public QPInterface
60
62
CSC_Matrix P, CSC_Matrix A, const std::vector<double > & q, const std::vector<double > & l,
61
63
const std::vector<double > & u);
62
64
63
- int getIteration () const override ;
64
- int getStatus () const override ;
65
+ int getIterationNumber () const override ;
66
+ bool isSolved () const override ;
67
+ std::string getStatus () const override ;
68
+
65
69
int getPolishStatus () const ;
66
70
std::vector<double > getDualSolution () const ;
67
71
@@ -96,20 +100,18 @@ class OSQPInterface : public QPInterface
96
100
void updateCheckTermination (const int check_termination);
97
101
98
102
// / \brief Get the number of iteration taken to solve the problem
99
- inline int64_t getTakenIter () const { return static_cast <int64_t >(m_latest_work_info .iter ); }
103
+ inline int64_t getTakenIter () const { return static_cast <int64_t >(latest_work_info_ .iter ); }
100
104
// / \brief Get the status message for the latest problem solved
101
105
inline std::string getStatusMessage () const
102
106
{
103
- return static_cast <std::string>(m_latest_work_info .status );
107
+ return static_cast <std::string>(latest_work_info_ .status );
104
108
}
105
109
// / \brief Get the runtime of the latest problem solved
106
- inline double getRunTime () const { return m_latest_work_info .run_time ; }
110
+ inline double getRunTime () const { return latest_work_info_ .run_time ; }
107
111
// / \brief Get the objective value the latest problem solved
108
- inline double getObjVal () const { return m_latest_work_info .obj_val ; }
112
+ inline double getObjVal () const { return latest_work_info_ .obj_val ; }
109
113
// / \brief Returns flag asserting interface condition (Healthy condition: 0).
110
- inline int64_t getExitFlag () const { return m_exitflag; }
111
-
112
- void logUnsolvedStatus (const std::string & prefix_message = " " ) const ;
114
+ inline int64_t getExitFlag () const { return exitflag_; }
113
115
114
116
// Setter functions for warm start
115
117
bool setWarmStart (
@@ -118,17 +120,17 @@ class OSQPInterface : public QPInterface
118
120
bool setDualVariables (const std::vector<double > & dual_variables);
119
121
120
122
private:
121
- std::unique_ptr<OSQPWorkspace, std::function<void (OSQPWorkspace *)>> m_work ;
122
- std::unique_ptr<OSQPSettings> m_settings ;
123
- std::unique_ptr<OSQPData> m_data ;
123
+ std::unique_ptr<OSQPWorkspace, std::function<void (OSQPWorkspace *)>> work_ ;
124
+ std::unique_ptr<OSQPSettings> settings_ ;
125
+ std::unique_ptr<OSQPData> data_ ;
124
126
// store last work info since work is cleaned up at every execution to prevent memory leak.
125
- OSQPInfo m_latest_work_info ;
127
+ OSQPInfo latest_work_info_ ;
126
128
// Number of parameters to optimize
127
- int64_t m_param_n ;
129
+ int64_t param_n_ ;
128
130
// Flag to check if the current work exists
129
- bool m_work_initialized = false ;
131
+ bool work__initialized = false ;
130
132
// Exitflag
131
- int64_t m_exitflag ;
133
+ int64_t exitflag_ ;
132
134
133
135
void initializeProblemImpl (
134
136
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double > & q,
@@ -140,6 +142,6 @@ class OSQPInterface : public QPInterface
140
142
141
143
std::vector<double > optimizeImpl () override ;
142
144
};
143
- } // namespace qp
145
+ } // namespace autoware::common
144
146
145
147
#endif // QP_INTERFACE__OSQP_INTERFACE_HPP_
0 commit comments