This unit test considers a variety of different solver/algorithm options for NLOC, combined with a linear system. We check if the optimization converges within 1 iteration.
#pragma once
#include <chrono>
#include <gtest/gtest.h>
#include "../testSystems/LinearOscillator.h"
namespace optcon {
namespace example {
using std::shared_ptr;
TEST(LinearSystemsTest, NLOCSolverTest)
{
size_t testCounter = 0;
Eigen::Vector2d x_final;
x_final << 20, 0;
initState.setZero();
initState(1) = 1.0;
nloc_settings.
discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER;
nloc_settings.
lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER;
for (int algClass = 0; algClass < NLOptConSettings::NLOCP_ALGORITHM::NUM_TYPES; algClass++)
{
for (int toggleLS = 0; toggleLS <= 1; toggleLS++)
{
for (size_t nThreads = 1; nThreads < 5; nThreads = nThreads + 3)
{
for (size_t kshot = 1; kshot < 11; kshot = kshot + 9)
{
if (kshot > 1 && nloc_settings.
nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::ILQR)
continue;
for (size_t sensInt = 0; sensInt <= 1; sensInt++)
{
for (size_t ksim = 1; ksim <= 5; ksim = ksim + 4)
{
nloc_settings.
K_sim = ksim;
continue;
for (size_t integratortype = 0; integratortype <= 1; integratortype++)
{
if (integratortype == 0)
nloc_settings.
integrator =
ct::core::IntegrationType::EULERCT;
{
nloc_settings.
integrator =
ct::core::IntegrationType::RK4CT;
}
else
continue;
shared_ptr<ControlledSystem<state_dim, control_dim>> nonlinearSystem(
shared_ptr<LinearSystem<state_dim, control_dim>> analyticLinearSystem(
shared_ptr<CostFunctionQuadratic<state_dim, control_dim>> costFunction =
tpl::createCostFunctionLinearOscillator<double>(x_final);
size_t nSteps = nloc_settings.
computeK(tf);
tf, x0[0], nonlinearSystem, costFunction, analyticLinearSystem);
ASSERT_GT(summary.
lx_norms.front(), 1e-9);
ASSERT_GT(summary.
lu_norms.front(), 1e-9);
ASSERT_LT(summary.
lx_norms.back(), 1e-10);
ASSERT_LT(summary.
lu_norms.back(), 1e-10);
testCounter++;
}
}
}
}
}
}
}
std::cout << "Performed " << testCounter << " successful NLOC tests with linear systems" << std::endl;
}
}
}
}