Skip to content

Commit fcf9ab1

Browse files
PanConChicharronpre-commit-ci[bot]youtalk
authored
feat(osqp_interface): core changes for additional failure logging (#281)
* fix Signed-off-by: Arjun Jagdish Ram <arjun.ram@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Arjun Jagdish Ram <arjun.ram@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <yutaka.kondo@youtalk.jp>
1 parent 9ebdf7f commit fcf9ab1

File tree

5 files changed

+94
-46
lines changed

5 files changed

+94
-46
lines changed

common/autoware_osqp_interface/design/osqp_interface-design.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ The interface can be used in several ways:
5454

5555
```cpp
5656
std::tuple<std::vector<double>, std::vector<double>> result = osqp_interface.optimize();
57-
std::vector<double> param = std::get<0>(result);
57+
std::vector<double> param = result.primal_solution;
5858
double x_0 = param[0];
5959
double x_1 = param[1];
6060
```

common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp

+38
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,44 @@ struct OSQP_INTERFACE_PUBLIC CSC_Matrix
3333
std::vector<c_int> m_row_idxs;
3434
/// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer')
3535
std::vector<c_int> m_col_idxs;
36+
37+
friend std::ostream & operator<<(std::ostream & os, const CSC_Matrix & matrix)
38+
{
39+
os << "CSC_Matrix: {\n";
40+
os << "\tm_vals: [";
41+
42+
// Iterator-based loop for m_vals
43+
for (auto it = std::begin(matrix.m_vals); it != std::end(matrix.m_vals); ++it) {
44+
os << *it; // Print the current element (dereference iterator)
45+
if (std::next(it) != std::end(matrix.m_vals)) { // Check if not the last element
46+
os << ", ";
47+
}
48+
}
49+
os << "],\n";
50+
51+
os << "\tm_row_idxs: [";
52+
// Iterator-based loop for m_row_idxs
53+
for (auto it = std::begin(matrix.m_row_idxs); it != std::end(matrix.m_row_idxs); ++it) {
54+
os << *it;
55+
if (std::next(it) != std::end(matrix.m_row_idxs)) {
56+
os << ", ";
57+
}
58+
}
59+
os << "],\n";
60+
61+
os << "\tm_col_idxs: [";
62+
// Iterator-based loop for m_col_idxs
63+
for (auto it = std::begin(matrix.m_col_idxs); it != std::end(matrix.m_col_idxs); ++it) {
64+
os << *it;
65+
if (std::next(it) != std::end(matrix.m_col_idxs)) {
66+
os << ", ";
67+
}
68+
}
69+
os << "]\n";
70+
71+
os << "}\n";
72+
return os;
73+
}
3674
};
3775

3876
/// \brief Calculate CSC matrix from Eigen matrix

common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp

+15-5
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,16 @@ namespace autoware::osqp_interface
3232
{
3333
constexpr c_float INF = 1e30;
3434

35+
struct OSQPResult
36+
{
37+
std::vector<double> primal_solution;
38+
std::vector<double> lagrange_multipliers;
39+
int polish_status;
40+
int solution_status;
41+
int iteration_status;
42+
int exit_flag;
43+
};
44+
3545
/**
3646
* Implementation of a native C++ interface for the OSQP solver.
3747
*
@@ -52,7 +62,7 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface
5262
int64_t m_exitflag;
5363

5464
// Runs the solver on the stored problem.
55-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> solve();
65+
OSQPResult solve();
5666

5767
static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept;
5868

@@ -93,10 +103,10 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface
93103
/// \details std::tuple<std::vector<double>, std::vector<double>> result;
94104
/// \details result = osqp_interface.optimize();
95105
/// \details 4. Access the optimized parameters.
96-
/// \details std::vector<float> param = std::get<0>(result);
106+
/// \details std::vector<float> param = result.primal_solution;
97107
/// \details double x_0 = param[0];
98108
/// \details double x_1 = param[1];
99-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> optimize();
109+
OSQPResult optimize();
100110

101111
/// \brief Solves convex quadratic programs (QPs) using the OSQP solver.
102112
/// \return The function returns a tuple containing the solution as two float vectors.
@@ -111,10 +121,10 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface
111121
/// \details std::tuple<std::vector<double>, std::vector<double>> result;
112122
/// \details result = osqp_interface.optimize(P, A, q, l, u, 1e-6);
113123
/// \details 4. Access the optimized parameters.
114-
/// \details std::vector<float> param = std::get<0>(result);
124+
/// \details std::vector<float> param = result.primal_solution;
115125
/// \details double x_0 = param[0];
116126
/// \details double x_1 = param[1];
117-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> optimize(
127+
OSQPResult optimize(
118128
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
119129
const std::vector<double> & l, const std::vector<double> & u);
120130

common/autoware_osqp_interface/src/osqp_interface.cpp

+14-12
Original file line numberDiff line numberDiff line change
@@ -359,11 +359,10 @@ int64_t OSQPInterface::initializeProblem(
359359
return m_exitflag;
360360
}
361361

362-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t>
363-
OSQPInterface::solve()
362+
OSQPResult OSQPInterface::solve()
364363
{
365364
// Solve Problem
366-
osqp_solve(m_work.get());
365+
int32_t exit_flag = osqp_solve(m_work.get());
367366

368367
/********************
369368
* EXTRACT SOLUTION
@@ -378,33 +377,36 @@ OSQPInterface::solve()
378377
int64_t status_iteration = m_work->info->iter;
379378

380379
// Result tuple
381-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> result =
382-
std::make_tuple(
383-
sol_primal, sol_lagrange_multiplier, status_polish, status_solution, status_iteration);
380+
OSQPResult result;
381+
382+
result.primal_solution = sol_primal;
383+
result.lagrange_multipliers = sol_lagrange_multiplier;
384+
result.polish_status = status_polish;
385+
result.solution_status = status_solution;
386+
result.iteration_status = status_iteration;
387+
result.exit_flag = exit_flag;
384388

385389
m_latest_work_info = *(m_work->info);
386390

387391
return result;
388392
}
389393

390-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t>
391-
OSQPInterface::optimize()
394+
OSQPResult OSQPInterface::optimize()
392395
{
393396
// Run the solver on the stored problem representation.
394-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> result = solve();
397+
OSQPResult result = solve();
395398
return result;
396399
}
397400

398-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t>
399-
OSQPInterface::optimize(
401+
OSQPResult OSQPInterface::optimize(
400402
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
401403
const std::vector<double> & l, const std::vector<double> & u)
402404
{
403405
// Allocate memory for problem
404406
initializeProblem(P, A, q, l, u);
405407

406408
// Run the solver on the stored problem representation.
407-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> result = solve();
409+
OSQPResult result = solve();
408410

409411
m_work.reset();
410412
m_work_initialized = false;

common/autoware_osqp_interface/test/test_osqp_interface.cpp

+26-28
Original file line numberDiff line numberDiff line change
@@ -44,25 +44,24 @@ TEST(TestOsqpInterface, BasicQp)
4444
using autoware::osqp_interface::calCSCMatrixTrapezoidal;
4545
using autoware::osqp_interface::CSC_Matrix;
4646

47-
auto check_result =
48-
[](const std::tuple<std::vector<double>, std::vector<double>, int, int, int> & result) {
49-
EXPECT_EQ(std::get<2>(result), 1); // polish succeeded
50-
EXPECT_EQ(std::get<3>(result), 1); // solution succeeded
51-
52-
static const auto ep = 1.0e-8;
53-
54-
const auto prime_val = std::get<0>(result);
55-
ASSERT_EQ(prime_val.size(), size_t(2));
56-
EXPECT_NEAR(prime_val[0], 0.3, ep);
57-
EXPECT_NEAR(prime_val[1], 0.7, ep);
58-
59-
const auto dual_val = std::get<1>(result);
60-
ASSERT_EQ(dual_val.size(), size_t(4));
61-
EXPECT_NEAR(dual_val[0], -2.9, ep);
62-
EXPECT_NEAR(dual_val[1], 0.0, ep);
63-
EXPECT_NEAR(dual_val[2], 0.2, ep);
64-
EXPECT_NEAR(dual_val[3], 0.0, ep);
65-
};
47+
auto check_result = [](const autoware::osqp_interface::OSQPResult & result) {
48+
EXPECT_EQ(result.polish_status, 1); // polish succeeded
49+
EXPECT_EQ(result.solution_status, 1); // solution succeeded
50+
51+
static const auto ep = 1.0e-8;
52+
53+
const auto prime_val = result.primal_solution;
54+
ASSERT_EQ(prime_val.size(), size_t(2));
55+
EXPECT_NEAR(prime_val[0], 0.3, ep);
56+
EXPECT_NEAR(prime_val[1], 0.7, ep);
57+
58+
const auto dual_val = result.lagrange_multipliers;
59+
ASSERT_EQ(dual_val.size(), size_t(4));
60+
EXPECT_NEAR(dual_val[0], -2.9, ep);
61+
EXPECT_NEAR(dual_val[1], 0.0, ep);
62+
EXPECT_NEAR(dual_val[2], 0.2, ep);
63+
EXPECT_NEAR(dual_val[3], 0.0, ep);
64+
};
6665

6766
const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished();
6867
const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished();
@@ -73,20 +72,19 @@ TEST(TestOsqpInterface, BasicQp)
7372
{
7473
// Define problem during optimization
7574
autoware::osqp_interface::OSQPInterface osqp;
76-
std::tuple<std::vector<double>, std::vector<double>, int, int, int> result =
77-
osqp.optimize(P, A, q, l, u);
75+
autoware::osqp_interface::OSQPResult result = osqp.optimize(P, A, q, l, u);
7876
check_result(result);
7977
}
8078

8179
{
8280
// Define problem during initialization
8381
autoware::osqp_interface::OSQPInterface osqp(P, A, q, l, u, 1e-6);
84-
std::tuple<std::vector<double>, std::vector<double>, int, int, int> result = osqp.optimize();
82+
autoware::osqp_interface::OSQPResult result = osqp.optimize();
8583
check_result(result);
8684
}
8785

8886
{
89-
std::tuple<std::vector<double>, std::vector<double>, int, int, int> result;
87+
autoware::osqp_interface::OSQPResult result;
9088
// Dummy initial problem
9189
Eigen::MatrixXd P_ini = Eigen::MatrixXd::Zero(2, 2);
9290
Eigen::MatrixXd A_ini = Eigen::MatrixXd::Zero(4, 2);
@@ -107,12 +105,12 @@ TEST(TestOsqpInterface, BasicQp)
107105
CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P);
108106
CSC_Matrix A_csc = calCSCMatrix(A);
109107
autoware::osqp_interface::OSQPInterface osqp(P_csc, A_csc, q, l, u, 1e-6);
110-
std::tuple<std::vector<double>, std::vector<double>, int, int, int> result = osqp.optimize();
108+
autoware::osqp_interface::OSQPResult result = osqp.optimize();
111109
check_result(result);
112110
}
113111

114112
{
115-
std::tuple<std::vector<double>, std::vector<double>, int, int, int> result;
113+
autoware::osqp_interface::OSQPResult result;
116114
// Dummy initial problem with csc matrix
117115
CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2));
118116
CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2));
@@ -132,7 +130,7 @@ TEST(TestOsqpInterface, BasicQp)
132130

133131
// add warm startup
134132
{
135-
std::tuple<std::vector<double>, std::vector<double>, int, int, int> result;
133+
autoware::osqp_interface::OSQPResult result;
136134
// Dummy initial problem with csc matrix
137135
CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2));
138136
CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2));
@@ -150,8 +148,8 @@ TEST(TestOsqpInterface, BasicQp)
150148
check_result(result);
151149

152150
osqp.updateCheckTermination(1);
153-
const auto primal_val = std::get<0>(result);
154-
const auto dual_val = std::get<1>(result);
151+
const auto primal_val = result.primal_solution;
152+
const auto dual_val = result.lagrange_multipliers;
155153
for (size_t i = 0; i < primal_val.size(); ++i) {
156154
std::cerr << primal_val.at(i) << std::endl;
157155
}

0 commit comments

Comments
 (0)