diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp index a5777dd545..2aa1f97204 100644 --- a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp +++ b/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp @@ -27,13 +27,14 @@ namespace autoware::qp_interface { constexpr c_float OSQP_INF = 1e30; +constexpr int OSQP_MAX_ITERATION = 20000; class OSQPInterface : public QPInterface { public: /// \brief Constructor without problem formulation OSQPInterface( - const bool enable_warm_start = false, const int max_iteration = 20000, + const bool enable_warm_start = false, const int max_iteration = OSQP_MAX_ITERATION, const c_float eps_abs = std::numeric_limits::epsilon(), const c_float eps_rel = std::numeric_limits::epsilon(), const bool polish = true, const bool verbose = false); diff --git a/common/autoware_qp_interface/src/osqp_interface.cpp b/common/autoware_qp_interface/src/osqp_interface.cpp index fbb8e71f4c..89a0b10e08 100644 --- a/common/autoware_qp_interface/src/osqp_interface.cpp +++ b/common/autoware_qp_interface/src/osqp_interface.cpp @@ -52,7 +52,7 @@ OSQPInterface::OSQPInterface( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u, const bool enable_warm_start, const c_float eps_abs) -: OSQPInterface(enable_warm_start, eps_abs) +: OSQPInterface(enable_warm_start, OSQP_MAX_ITERATION, eps_abs) { initializeProblem(P, A, q, l, u); } @@ -61,7 +61,7 @@ OSQPInterface::OSQPInterface( const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, const std::vector & l, const std::vector & u, const bool enable_warm_start, const c_float eps_abs) -: OSQPInterface(enable_warm_start, eps_abs) +: OSQPInterface(enable_warm_start, OSQP_MAX_ITERATION, eps_abs) { initializeCSCProblemImpl(P, A, q, l, u); }