This tutorial example shows how to use the MPC class. In the CT, every optimal control solver can be wrapped into the MPC-class, allowing for very rapid prototyping of different MPC applications. In this example, we apply iLQR-MPC to a simple second order system, a damped oscillator. This tutorial builds up on the example NLOC.cpp, please consider this one as well.
int main(
int argc,
char** argv)
{
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(
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);
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++)
{
auto current_time = std::chrono::high_resolution_clock::now();
1e-6 * std::chrono::duration_cast<std::chrono::microseconds>(current_time - start_time).count();
current_time = std::chrono::high_resolution_clock::now();
t = 1e-6 * std::chrono::duration_cast<std::chrono::microseconds>(current_time - start_time).count();
break;
}
}