Skip to content

Commit 4ae5163

Browse files
committed
feat(autoware_qp_interface): porting autoware_qp_interface package from autoware.universe
Signed-off-by: NorahXiong <norah.xiong@autocore.ai>
1 parent 2f8f677 commit 4ae5163

15 files changed

+1725
-0
lines changed
+81
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package autoware_qp_interface
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4+
5+
0.40.0 (2024-12-12)
6+
-------------------
7+
* Merge branch 'main' into release-0.40.0
8+
* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 <https://github.com/autowarefoundation/autoware.universe/issues/9587>`_)"
9+
This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
10+
* fix: fix ticket links in CHANGELOG.rst (`#9588 <https://github.com/autowarefoundation/autoware.universe/issues/9588>`_)
11+
* chore(package.xml): bump version to 0.39.0 (`#9587 <https://github.com/autowarefoundation/autoware.universe/issues/9587>`_)
12+
* chore(package.xml): bump version to 0.39.0
13+
* fix: fix ticket links in CHANGELOG.rst
14+
* fix: remove unnecessary diff
15+
---------
16+
Co-authored-by: Yutaka Kondo <yutaka.kondo@youtalk.jp>
17+
* fix: fix ticket links in CHANGELOG.rst (`#9588 <https://github.com/autowarefoundation/autoware.universe/issues/9588>`_)
18+
* fix(cpplint): include what you use - common (`#9564 <https://github.com/autowarefoundation/autoware.universe/issues/9564>`_)
19+
* fix: fix package names in changelog files (`#9500 <https://github.com/autowarefoundation/autoware.universe/issues/9500>`_)
20+
* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 <https://github.com/autowarefoundation/autoware.universe/issues/9440>`_)
21+
* 0.39.0
22+
* update changelog
23+
* Merge commit '6a1ddbd08bd' into release-0.39.0
24+
* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 <https://github.com/autowarefoundation/autoware.universe/issues/9304>`_)
25+
* chore(package.xml): bump version to 0.38.0 (`#9266 <https://github.com/autowarefoundation/autoware.universe/issues/9266>`_) (`#9284 <https://github.com/autowarefoundation/autoware.universe/issues/9284>`_)
26+
* unify package.xml version to 0.37.0
27+
* remove system_monitor/CHANGELOG.rst
28+
* add changelog
29+
* 0.38.0
30+
---------
31+
* refactor(qp_interface): prefix package and namespace with autoware (`#9236 <https://github.com/autowarefoundation/autoware.universe/issues/9236>`_)
32+
* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo
33+
34+
0.39.0 (2024-11-25)
35+
-------------------
36+
* Merge commit '6a1ddbd08bd' into release-0.39.0
37+
* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 <https://github.com/autowarefoundation/autoware.universe/issues/9304>`_)
38+
* chore(package.xml): bump version to 0.38.0 (`#9266 <https://github.com/autowarefoundation/autoware.universe/issues/9266>`_) (`#9284 <https://github.com/autowarefoundation/autoware.universe/issues/9284>`_)
39+
* unify package.xml version to 0.37.0
40+
* remove system_monitor/CHANGELOG.rst
41+
* add changelog
42+
* 0.38.0
43+
---------
44+
* refactor(qp_interface): prefix package and namespace with autoware (`#9236 <https://github.com/autowarefoundation/autoware.universe/issues/9236>`_)
45+
* Contributors: Esteve Fernandez, Yutaka Kondo
46+
47+
0.38.0 (2024-11-08)
48+
-------------------
49+
* unify package.xml version to 0.37.0
50+
* fix(qp_interface): fix unreadVariable (`#8349 <https://github.com/autowarefoundation/autoware.universe/issues/8349>`_)
51+
* fix:unreadVariable
52+
* fix:unreadVariable
53+
* fix:unreadVariable
54+
---------
55+
* perf(velocity_smoother): use ProxQP for faster optimization (`#8028 <https://github.com/autowarefoundation/autoware.universe/issues/8028>`_)
56+
* perf(velocity_smoother): use ProxQP for faster optimization
57+
* consider max_iteration
58+
* disable warm start
59+
* fix test
60+
---------
61+
* refactor(qp_interface): clean up the code (`#8029 <https://github.com/autowarefoundation/autoware.universe/issues/8029>`_)
62+
* refactor qp_interface
63+
* variable names: m_XXX -> XXX\_
64+
* update
65+
* update
66+
---------
67+
* fix(fake_test_node, osqp_interface, qp_interface): remove unnecessary cppcheck inline suppressions (`#7855 <https://github.com/autowarefoundation/autoware.universe/issues/7855>`_)
68+
* fix(fake_test_node, osqp_interface, qp_interface): remove unnecessary cppcheck inline suppressions
69+
* style(pre-commit): autofix
70+
---------
71+
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
72+
* Contributors: Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, kobayu858
73+
74+
0.26.0 (2024-04-03)
75+
-------------------
76+
* feat(qp_interface): support proxqp (`#3699 <https://github.com/autowarefoundation/autoware.universe/issues/3699>`_)
77+
* feat(qp_interface): add proxqp interface
78+
* update
79+
---------
80+
* feat(qp_interface): add new package which will contain various qp solvers (`#3697 <https://github.com/autowarefoundation/autoware.universe/issues/3697>`_)
81+
* Contributors: Takayuki Murooka
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
cmake_minimum_required(VERSION 3.14)
2+
project(autoware_qp_interface)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
7+
find_package(Eigen3 REQUIRED)
8+
find_package(proxsuite REQUIRED)
9+
10+
# after find_package(osqp_vendor) in ament_auto_find_build_dependencies
11+
find_package(osqp REQUIRED)
12+
get_target_property(OSQP_INCLUDE_SUB_DIR osqp::osqp INTERFACE_INCLUDE_DIRECTORIES)
13+
get_filename_component(OSQP_INCLUDE_DIR ${OSQP_INCLUDE_SUB_DIR} PATH)
14+
15+
set(QP_INTERFACE_LIB_SRC
16+
src/qp_interface.cpp
17+
src/osqp_interface.cpp
18+
src/osqp_csc_matrix_conv.cpp
19+
src/proxqp_interface.cpp
20+
)
21+
22+
set(QP_INTERFACE_LIB_HEADERS
23+
include/autoware/qp_interface/qp_interface.hpp
24+
include/autoware/qp_interface/osqp_interface.hpp
25+
include/autoware/qp_interface/osqp_csc_matrix_conv.hpp
26+
include/autoware/qp_interface/proxqp_interface.hpp
27+
)
28+
29+
ament_auto_add_library(${PROJECT_NAME} SHARED
30+
${QP_INTERFACE_LIB_SRC}
31+
${QP_INTERFACE_LIB_HEADERS}
32+
)
33+
target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast)
34+
35+
target_include_directories(${PROJECT_NAME}
36+
SYSTEM PUBLIC
37+
"${OSQP_INCLUDE_DIR}"
38+
"${EIGEN3_INCLUDE_DIR}"
39+
)
40+
41+
ament_target_dependencies(${PROJECT_NAME}
42+
Eigen3
43+
osqp_vendor
44+
proxsuite
45+
)
46+
47+
# crucial so downstream package builds because osqp_interface exposes osqp.hpp
48+
ament_export_include_directories("${OSQP_INCLUDE_DIR}")
49+
# crucial so the linking order is correct in a downstream package: libosqp_interface.a should come before libosqp.a
50+
ament_export_libraries(osqp::osqp)
51+
52+
if(BUILD_TESTING)
53+
set(TEST_SOURCES
54+
test/test_osqp_interface.cpp
55+
test/test_csc_matrix_conv.cpp
56+
test/test_proxqp_interface.cpp
57+
)
58+
set(TEST_OSQP_INTERFACE_EXE test_osqp_interface)
59+
ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES})
60+
target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME})
61+
endif()
62+
63+
ament_auto_package(INSTALL_TO_SHARE
64+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
# Interface for QP solvers
2+
3+
This is the design document for the `autoware_qp_interface` package.
4+
5+
## Purpose / Use cases
6+
7+
This packages provides a C++ interface for QP solvers.
8+
Currently, supported QP solvers are
9+
10+
- [OSQP library](https://osqp.org/docs/solver/index.html)
11+
12+
## Design
13+
14+
The class `QPInterface` takes a problem formulation as Eigen matrices and vectors, converts these objects into
15+
C-style Compressed-Column-Sparse matrices and dynamic arrays, loads the data into the QP workspace dataholder, and runs the optimizer.
16+
17+
## Inputs / Outputs / API
18+
19+
The interface can be used in several ways:
20+
21+
1. Initialize the interface, and load the problem formulation at the optimization call.
22+
23+
```cpp
24+
QPInterface qp_interface;
25+
qp_interface.optimize(P, A, q, l, u);
26+
```
27+
28+
2. WARM START OPTIMIZATION by modifying the problem formulation between optimization runs.
29+
30+
```cpp
31+
QPInterface qp_interface(true);
32+
qp_interface.optimize(P, A, q, l, u);
33+
qp_interface.optimize(P_new, A_new, q_new, l_new, u_new);
34+
```
35+
36+
The optimization results are returned as a vector by the optimization function.
37+
38+
```cpp
39+
const auto solution = qp_interface.optimize();
40+
double x_0 = solution[0];
41+
double x_1 = solution[1];
42+
```
43+
44+
## References / External links
45+
46+
- OSQP library: <https://osqp.org/>
47+
48+
## Related issues
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
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_CSC_MATRIX_CONV_HPP_
16+
#define AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_
17+
18+
#include "osqp/glob_opts.h"
19+
20+
#include <Eigen/Core>
21+
22+
#include <vector>
23+
24+
namespace autoware::qp_interface
25+
{
26+
/// \brief Compressed-Column-Sparse Matrix
27+
struct CSC_Matrix
28+
{
29+
/// Vector of non-zero values. Ex: [4,1,1,2]
30+
std::vector<c_float> vals_;
31+
/// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner')
32+
std::vector<c_int> row_idxs_;
33+
/// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer')
34+
std::vector<c_int> col_idxs_;
35+
};
36+
37+
/// \brief Calculate CSC matrix from Eigen matrix
38+
CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat);
39+
/// \brief Calculate upper trapezoidal CSC matrix from square Eigen matrix
40+
CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat);
41+
/// \brief Print the given CSC matrix to the standard output
42+
void printCSCMatrix(const CSC_Matrix & csc_mat);
43+
44+
} // namespace autoware::qp_interface
45+
46+
#endif // AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,147 @@
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

Comments
 (0)