Skip to content

Commit 1854179

Browse files
conditional timer - MRM trigger
Signed-off-by: Arjun Jagdish Ram <arjun.ram@tier4.jp>
1 parent b992481 commit 1854179

File tree

17 files changed

+397
-84
lines changed

17 files changed

+397
-84
lines changed

common/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/osqp_interface/include/osqp_interface/csc_matrix_conv.hpp

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

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

common/osqp_interface/include/osqp_interface/osqp_interface.hpp

+15-5
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,16 @@ namespace osqp
3636
{
3737
constexpr c_float INF = 1e30;
3838

39+
struct OSQPResult
40+
{
41+
std::vector<double> primal_solution;
42+
std::vector<double> lagrange_multipliers;
43+
int polish_status;
44+
int solution_status;
45+
int iteration_status;
46+
int exit_flag;
47+
};
48+
3949
/**
4050
* Implementation of a native C++ interface for the OSQP solver.
4151
*
@@ -56,7 +66,7 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface
5666
int64_t m_exitflag;
5767

5868
// Runs the solver on the stored problem.
59-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> solve();
69+
OSQPResult solve();
6070

6171
static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept;
6272

@@ -97,10 +107,10 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface
97107
/// \details std::tuple<std::vector<double>, std::vector<double>> result;
98108
/// \details result = osqp_interface.optimize();
99109
/// \details 4. Access the optimized parameters.
100-
/// \details std::vector<float> param = std::get<0>(result);
110+
/// \details std::vector<float> param = result.primal_solution;
101111
/// \details double x_0 = param[0];
102112
/// \details double x_1 = param[1];
103-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> optimize();
113+
OSQPResult optimize();
104114

105115
/// \brief Solves convex quadratic programs (QPs) using the OSQP solver.
106116
/// \return The function returns a tuple containing the solution as two float vectors.
@@ -115,10 +125,10 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface
115125
/// \details std::tuple<std::vector<double>, std::vector<double>> result;
116126
/// \details result = osqp_interface.optimize(P, A, q, l, u, 1e-6);
117127
/// \details 4. Access the optimized parameters.
118-
/// \details std::vector<float> param = std::get<0>(result);
128+
/// \details std::vector<float> param = result.primal_solution;
119129
/// \details double x_0 = param[0];
120130
/// \details double x_1 = param[1];
121-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> optimize(
131+
OSQPResult optimize(
122132
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
123133
const std::vector<double> & l, const std::vector<double> & u);
124134

common/osqp_interface/src/osqp_interface.cpp

+14-12
Original file line numberDiff line numberDiff line change
@@ -363,11 +363,10 @@ int64_t OSQPInterface::initializeProblem(
363363
return m_exitflag;
364364
}
365365

366-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t>
367-
OSQPInterface::solve()
366+
OSQPResult OSQPInterface::solve()
368367
{
369368
// Solve Problem
370-
osqp_solve(m_work.get());
369+
int32_t exit_flag = osqp_solve(m_work.get());
371370

372371
/********************
373372
* EXTRACT SOLUTION
@@ -382,33 +381,36 @@ OSQPInterface::solve()
382381
int64_t status_iteration = m_work->info->iter;
383382

384383
// Result tuple
385-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> result =
386-
std::make_tuple(
387-
sol_primal, sol_lagrange_multiplier, status_polish, status_solution, status_iteration);
384+
OSQPResult result;
385+
386+
result.primal_solution = sol_primal;
387+
result.lagrange_multipliers = sol_lagrange_multiplier;
388+
result.polish_status = status_polish;
389+
result.solution_status = status_solution;
390+
result.iteration_status = status_iteration;
391+
result.exit_flag = exit_flag;
388392

389393
m_latest_work_info = *(m_work->info);
390394

391395
return result;
392396
}
393397

394-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t>
395-
OSQPInterface::optimize()
398+
OSQPResult OSQPInterface::optimize()
396399
{
397400
// Run the solver on the stored problem representation.
398-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> result = solve();
401+
OSQPResult result = solve();
399402
return result;
400403
}
401404

402-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t>
403-
OSQPInterface::optimize(
405+
OSQPResult OSQPInterface::optimize(
404406
const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector<double> & q,
405407
const std::vector<double> & l, const std::vector<double> & u)
406408
{
407409
// Allocate memory for problem
408410
initializeProblem(P, A, q, l, u);
409411

410412
// Run the solver on the stored problem representation.
411-
std::tuple<std::vector<double>, std::vector<double>, int64_t, int64_t, int64_t> result = solve();
413+
OSQPResult result = solve();
412414

413415
m_work.reset();
414416
m_work_initialized = false;

common/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::common::osqp::calCSCMatrixTrapezoidal;
4545
using autoware::common::osqp::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::common::osqp::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::common::osqp::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::common::osqp::OSQPResult result = osqp.optimize(P, A, q, l, u);
7876
check_result(result);
7977
}
8078

8179
{
8280
// Define problem during initialization
8381
autoware::common::osqp::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::common::osqp::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::common::osqp::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::common::osqp::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::common::osqp::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::common::osqp::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::common::osqp::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
}

control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -54,11 +54,11 @@ bool QPSolverOSQP::solve(
5454
/* execute optimization */
5555
auto result = osqpsolver_.optimize(h_mat, osqpA, f, lower_bound, upper_bound);
5656

57-
std::vector<double> U_osqp = std::get<0>(result);
57+
std::vector<double> U_osqp = result.primal_solution;
5858
u = Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, 1>>(
5959
&U_osqp[0], static_cast<Eigen::Index>(U_osqp.size()), 1);
6060

61-
const int status_val = std::get<3>(result);
61+
const int status_val = result.solution_status;
6262
if (status_val != 1) {
6363
RCLCPP_WARN(logger_, "optimization failed : %s", osqpsolver_.getStatusMessage().c_str());
6464
return false;
@@ -71,7 +71,7 @@ bool QPSolverOSQP::solve(
7171
}
7272

7373
// polish status: successful (1), unperformed (0), (-1) unsuccessful
74-
int status_polish = std::get<2>(result);
74+
int status_polish = result.polish_status;
7575
if (status_polish == -1 || status_polish == 0) {
7676
const auto s = (status_polish == 0) ? "Polish process is not performed in osqp."
7777
: "Polish process failed in osqp.";

planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -244,10 +244,11 @@ VelocityOptimizer::OptimizationResult VelocityOptimizer::optimize(const Optimiza
244244
}
245245

246246
// execute optimization
247-
const auto result = qp_solver_.optimize(P, A, q, lower_bound, upper_bound);
248-
const std::vector<double> optval = std::get<0>(result);
247+
const autoware::common::osqp::OSQPResult result =
248+
qp_solver_.optimize(P, A, q, lower_bound, upper_bound);
249+
const std::vector<double> optval = result.primal_solution;
249250

250-
const int status_val = std::get<3>(result);
251+
const int status_val = result.solution_status;
251252
if (status_val != 1)
252253
std::cerr << "optimization failed : " << qp_solver_.getStatusMessage().c_str() << std::endl;
253254

0 commit comments

Comments
 (0)