In this example we show how to use a Nonlinear Optimal Control solver (here iLQG) in combination with the MPC-class for out-of-the box Model Predictive Control.
int main(
int argc,
char** argv)
{
double w_n = 0.1;
double zeta = 5.0;
std::shared_ptr<ct::core::SystemLinearizer<state_dim, control_dim>> adLinearizer(
std::shared_ptr<ct::optcon::TermQuadratic<state_dim, control_dim>> intermediateCost(
std::shared_ptr<ct::optcon::TermQuadratic<state_dim, control_dim>> finalCost(
bool verbose = true;
intermediateCost->loadConfigFile(ct::optcon::exampleDir + "/mpcCost.info", "intermediateCost", verbose);
finalCost->loadConfigFile(ct::optcon::exampleDir + "/mpcCost.info", "finalCost", verbose);
std::shared_ptr<CostFunctionQuadratic<state_dim, control_dim>> costFunction(
costFunction->addIntermediateTerm(intermediateCost);
costFunction->addFinalTerm(finalCost);
x0.setRandom();
timeHorizon, x0, oscillatorDynamics, costFunction, adLinearizer);
ilqr_settings.
integrator = ct::core::IntegrationType::EULERCT;
ilqr_settings.
discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER;
ilqr_settings.
lqocp_solver = NLOptConSettings::LQOCP_SOLVER::
GNRICCATI_SOLVER;
size_t K = ilqr_settings.
computeK(timeHorizon);
iLQR.setInitialGuess(initController);
iLQR.solve();
mpc_settings.
mpc_mode = ct::optcon::MPC_MODE::FIXED_FINAL_TIME;
ilqr_mpc.setInitialGuess(initialSolution);
auto start_time = std::chrono::high_resolution_clock::now();
size_t maxNumRuns = 100;
std::cout << "Starting to run MPC" << std::endl;
for (size_t i = 0; i < maxNumRuns; i++)
{
if (i > 0)
auto current_time = std::chrono::high_resolution_clock::now();
1e-6 * std::chrono::duration_cast<std::chrono::microseconds>(current_time - start_time).count();
ilqr_mpc.prepareIteration(t);
current_time = std::chrono::high_resolution_clock::now();
t = 1e-6 * std::chrono::duration_cast<std::chrono::microseconds>(current_time - start_time).count();
bool success = ilqr_mpc.finishIteration(x0, t, newPolicy, ts_newPolicy);
if (ilqr_mpc.timeHorizonReached() | !success)
break;
}
ilqr_mpc.printMpcSummary();
}