Skip to content

Commit ef096b9

Browse files
committed
hpipm_mode can be defined in configuration file
1 parent c9ebddf commit ef096b9

File tree

4 files changed

+31
-7
lines changed

4 files changed

+31
-7
lines changed

ct_optcon/examples/nlocSolver_ObstacleConstraint.info

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,5 +37,6 @@ ilqr
3737
{
3838
lqoc_debug_print false
3939
num_lqoc_iterations 50
40+
hpipm_mode_str SPEED
4041
}
4142
}

ct_optcon/include/ct/optcon/solver/NLOptConSettings.hpp

Lines changed: 15 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -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
154154
struct LQOCSolverSettings
155155
{
156156
public:
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

ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -139,6 +139,16 @@ void HPIPMInterface<STATE_DIM, CONTROL_DIM>::initializeAndAllocate()
139139
ipm_arg_mem_ = malloc(ipm_arg_size);
140140
::d_ocp_qp_ipm_arg_create(&dim_, &arg_, ipm_arg_mem_);
141141

142+
if (stringToHpipmMode.find(settings_.lqoc_solver_settings.hpipm_mode_str) != stringToHpipmMode.end())
143+
mode_ = stringToHpipmMode[settings_.lqoc_solver_settings.hpipm_mode_str];
144+
else
145+
{
146+
std::cout << "Invalid hpipm_mode_str specified in config, should be one of the following:" << std::endl;
147+
for (auto it = stringToHpipmMode.begin(); it != stringToHpipmMode.end(); it++)
148+
std::cout << it->first << std::endl;
149+
exit(-1);
150+
}
151+
142152
::d_ocp_qp_ipm_arg_set_default(mode_, &arg_);
143153
::d_ocp_qp_ipm_arg_set_iter_max(&settings_.lqoc_solver_settings.num_lqoc_iterations, &arg_);
144154

ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface.hpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -255,8 +255,11 @@ class HPIPMInterface : public LQOCSolver<STATE_DIM, CONTROL_DIM>
255255
struct d_ocp_qp_ipm_ws workspace_;
256256
int hpipm_status_; // status code after solving
257257

258-
// todo make this a setting
259-
::hpipm_mode mode_ = ::hpipm_mode::SPEED; // ROBUST/BALANCED; see also hpipm_common.h
258+
// hpipm mode SPEED_ABS, SPEED, ROBUST or BALANCED
259+
::hpipm_mode mode_; // see also hpipm_common.h
260+
261+
std::map<std::string, ::hpipm_mode> stringToHpipmMode = {{"SPEED_ABS", ::hpipm_mode::SPEED_ABS},
262+
{"SPEED", ::hpipm_mode::SPEED}, {"ROBUST", ::hpipm_mode::ROBUST}, {"BALANCE", ::hpipm_mode::BALANCE}};
260263
};
261264

262265
} // namespace optcon

0 commit comments

Comments
 (0)