@@ -24,9 +24,9 @@ struct LineSearchSettings
2424 // ! types of backtracking line-search
2525 enum TYPE
2626 {
27- NONE = 0 , // ! take full-step updates
28- SIMPLE, // ! simple backtracking using cost or merit function
29- ARMIJO, // ! backtracking including riccati matrix measure
27+ NONE = 0 , // ! take full-step updates
28+ SIMPLE, // ! simple backtracking using cost or merit function
29+ ARMIJO, // ! backtracking including riccati matrix measure
3030 GOLDSTEIN, // ! backtracking including riccati matrix measure and defects
3131 NUM_TYPES
3232 };
@@ -154,16 +154,20 @@ struct LineSearchSettings
154154struct LQOCSolverSettings
155155{
156156public:
157- LQOCSolverSettings () : lqoc_debug_print(false ), num_lqoc_iterations(10 ) {}
157+ LQOCSolverSettings () : lqoc_debug_print(false ), num_lqoc_iterations(10 ), hpipm_mode_str( " SPEED " ) {}
158158
159159 bool lqoc_debug_print;
160- int num_lqoc_iterations; // ! number of allowed sub-iterations of LQOC solver per NLOC main iteration
160+ int num_lqoc_iterations; // ! number of allowed sub-iterations of LQOC solver per NLOC main iteration
161+ std::string hpipm_mode_str; // HPIPM specific : SPEED_ABS, SPEED, ROBUST or BALANCED.
162+ // Stored as string and not as hpipm_mode enum because HPIPM is not a compulsory dependency.
163+ // (see https://github.com/giaf/hpipm/blob/f38a216c5a9f916682cd543f8992a594323ad202/ocp_qp/x_ocp_qp_ipm.c#L69)
161164
162165 void print () const
163166 {
164167 std::cout << " ======================= LQOCSolverSettings =====================" << std::endl;
165168 std::cout << " num_lqoc_iterations: \t " << num_lqoc_iterations << std::endl;
166169 std::cout << " lqoc_debug_print: \t " << lqoc_debug_print << std::endl;
170+ std::cout << " hpipm_mode_str: \t " << hpipm_mode_str << std::endl;
167171 }
168172
169173 void load (const std::string& filename, bool verbose = true , const std::string& ns = " lqoc_solver_settings" )
@@ -186,6 +190,12 @@ struct LQOCSolverSettings
186190 } catch (...)
187191 {
188192 }
193+ try
194+ {
195+ hpipm_mode_str = pt.get <std::string>(ns + " .hpipm_mode_str" );
196+ } catch (...)
197+ {
198+ }
189199 }
190200};
191201
0 commit comments