Skip to content

Commit ea5c06c

Browse files
takayuki5168Ariiees
authored andcommitted
refactor(qp_interface): clean up the code (autowarefoundation#8029)
* refactor qp_interface Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * variable names: m_XXX -> XXX_ Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * update Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * update Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 4f3013f commit ea5c06c

11 files changed

+377
-344
lines changed

common/qp_interface/include/qp_interface/osqp_csc_matrix_conv.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -21,17 +21,17 @@
2121

2222
#include <vector>
2323

24-
namespace qp
24+
namespace autoware::common
2525
{
2626
/// \brief Compressed-Column-Sparse Matrix
2727
struct CSC_Matrix
2828
{
2929
/// Vector of non-zero values. Ex: [4,1,1,2]
30-
std::vector<c_float> m_vals;
30+
std::vector<c_float> vals_;
3131
/// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner')
32-
std::vector<c_int> m_row_idxs;
32+
std::vector<c_int> row_idxs_;
3333
/// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer')
34-
std::vector<c_int> m_col_idxs;
34+
std::vector<c_int> col_idxs_;
3535
};
3636

3737
/// \brief Calculate CSC matrix from Eigen matrix
@@ -41,6 +41,6 @@ CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat);
4141
/// \brief Print the given CSC matrix to the standard output
4242
void printCSCMatrix(const CSC_Matrix & csc_mat);
4343

44-
} // namespace qp
44+
} // namespace autoware::common
4545

4646
#endif // QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_

common/qp_interface/include/qp_interface/osqp_interface.hpp

+22-20
Original file line numberDiff line numberDiff line change
@@ -24,17 +24,19 @@
2424
#include <string>
2525
#include <vector>
2626

27-
namespace qp
27+
namespace autoware::common
2828
{
29-
constexpr c_float INF = 1e30;
29+
constexpr c_float OSQP_INF = 1e30;
3030

3131
class OSQPInterface : public QPInterface
3232
{
3333
public:
3434
/// \brief Constructor without problem formulation
3535
OSQPInterface(
3636
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);
3840
/// \brief Constructor with problem setup
3941
/// \param P: (n,n) matrix defining relations between parameters.
4042
/// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound.
@@ -60,8 +62,10 @@ class OSQPInterface : public QPInterface
6062
CSC_Matrix P, CSC_Matrix A, const std::vector<double> & q, const std::vector<double> & l,
6163
const std::vector<double> & u);
6264

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+
6569
int getPolishStatus() const;
6670
std::vector<double> getDualSolution() const;
6771

@@ -96,20 +100,18 @@ class OSQPInterface : public QPInterface
96100
void updateCheckTermination(const int check_termination);
97101

98102
/// \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); }
100104
/// \brief Get the status message for the latest problem solved
101105
inline std::string getStatusMessage() const
102106
{
103-
return static_cast<std::string>(m_latest_work_info.status);
107+
return static_cast<std::string>(latest_work_info_.status);
104108
}
105109
/// \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; }
107111
/// \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; }
109113
/// \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_; }
113115

114116
// Setter functions for warm start
115117
bool setWarmStart(
@@ -118,17 +120,17 @@ class OSQPInterface : public QPInterface
118120
bool setDualVariables(const std::vector<double> & dual_variables);
119121

120122
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_;
124126
// 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_;
126128
// Number of parameters to optimize
127-
int64_t m_param_n;
129+
int64_t param_n_;
128130
// Flag to check if the current work exists
129-
bool m_work_initialized = false;
131+
bool work__initialized = false;
130132
// Exitflag
131-
int64_t m_exitflag;
133+
int64_t exitflag_;
132134

133135
void initializeProblemImpl(
134136
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
@@ -140,6 +142,6 @@ class OSQPInterface : public QPInterface
140142

141143
std::vector<double> optimizeImpl() override;
142144
};
143-
} // namespace qp
145+
} // namespace autoware::common
144146

145147
#endif // QP_INTERFACE__OSQP_INTERFACE_HPP_

common/qp_interface/include/qp_interface/proxqp_interface.hpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -22,34 +22,36 @@
2222

2323
#include <limits>
2424
#include <memory>
25+
#include <string>
2526
#include <vector>
2627

27-
namespace qp
28+
namespace autoware::common
2829
{
2930
class ProxQPInterface : public QPInterface
3031
{
3132
public:
3233
explicit ProxQPInterface(
33-
const bool enable_warm_start = false,
34-
const double eps_abs = std::numeric_limits<double>::epsilon());
34+
const bool enable_warm_start, const double eps_abs, const double eps_rel,
35+
const bool verbose = false);
3536

36-
int getIteration() const override;
37-
int getStatus() const override;
37+
int getIterationNumber() const override;
38+
bool isSolved() const override;
39+
std::string getStatus() const override;
3840

3941
void updateEpsAbs(const double eps_abs) override;
4042
void updateEpsRel(const double eps_rel) override;
4143
void updateVerbose(const bool verbose) override;
4244

4345
private:
44-
proxsuite::proxqp::Settings<double> m_settings;
45-
std::shared_ptr<proxsuite::proxqp::sparse::QP<double, int>> m_qp_ptr;
46+
proxsuite::proxqp::Settings<double> settings_{};
47+
std::shared_ptr<proxsuite::proxqp::sparse::QP<double, int>> qp_ptr_{nullptr};
4648

4749
void initializeProblemImpl(
4850
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
4951
const std::vector<double> & l, const std::vector<double> & u) override;
5052

5153
std::vector<double> optimizeImpl() override;
5254
};
53-
} // namespace qp
55+
} // namespace autoware::common
5456

5557
#endif // QP_INTERFACE__PROXQP_INTERFACE_HPP_

common/qp_interface/include/qp_interface/qp_interface.hpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -18,28 +18,30 @@
1818
#include <Eigen/Core>
1919

2020
#include <optional>
21+
#include <string>
2122
#include <vector>
2223

23-
namespace qp
24+
namespace autoware::common
2425
{
2526
class QPInterface
2627
{
2728
public:
28-
explicit QPInterface(const bool enable_warm_start) : m_enable_warm_start(enable_warm_start) {}
29+
explicit QPInterface(const bool enable_warm_start) : enable_warm_start_(enable_warm_start) {}
2930

3031
std::vector<double> optimize(
3132
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
3233
const std::vector<double> & l, const std::vector<double> & u);
3334

34-
virtual int getIteration() const = 0;
35-
virtual int getStatus() const = 0;
35+
virtual bool isSolved() const = 0;
36+
virtual int getIterationNumber() const = 0;
37+
virtual std::string getStatus() const = 0;
3638

3739
virtual void updateEpsAbs([[maybe_unused]] const double eps_abs) = 0;
3840
virtual void updateEpsRel([[maybe_unused]] const double eps_rel) = 0;
3941
virtual void updateVerbose([[maybe_unused]] const bool verbose) {}
4042

4143
protected:
42-
bool m_enable_warm_start;
44+
bool enable_warm_start_{false};
4345

4446
void initializeProblem(
4547
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
@@ -51,9 +53,9 @@ class QPInterface
5153

5254
virtual std::vector<double> optimizeImpl() = 0;
5355

54-
std::optional<size_t> m_variables_num;
55-
std::optional<size_t> m_constraints_num;
56+
std::optional<size_t> variables_num_{std::nullopt};
57+
std::optional<size_t> constraints_num_{std::nullopt};
5658
};
57-
} // namespace qp
59+
} // namespace autoware::common
5860

5961
#endif // QP_INTERFACE__QP_INTERFACE_HPP_

common/qp_interface/src/osqp_csc_matrix_conv.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
#include <iostream>
2222
#include <vector>
2323

24-
namespace qp
24+
namespace autoware::common
2525
{
2626
CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat)
2727
{
@@ -114,21 +114,21 @@ CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat)
114114
void printCSCMatrix(const CSC_Matrix & csc_mat)
115115
{
116116
std::cout << "[";
117-
for (const c_float & val : csc_mat.m_vals) {
117+
for (const c_float & val : csc_mat.vals_) {
118118
std::cout << val << ", ";
119119
}
120120
std::cout << "]\n";
121121

122122
std::cout << "[";
123-
for (const c_int & row : csc_mat.m_row_idxs) {
123+
for (const c_int & row : csc_mat.row_idxs_) {
124124
std::cout << row << ", ";
125125
}
126126
std::cout << "]\n";
127127

128128
std::cout << "[";
129-
for (const c_int & col : csc_mat.m_col_idxs) {
129+
for (const c_int & col : csc_mat.col_idxs_) {
130130
std::cout << col << ", ";
131131
}
132132
std::cout << "]\n";
133133
}
134-
} // namespace qp
134+
} // namespace autoware::common

0 commit comments

Comments
 (0)