This test implements iLQR and GNMS for a symplectic system.
#include <chrono>
#include <gtest/gtest.h>
namespace optcon {
namespace example {
using std::shared_ptr;
{
public:
{
pDot = v;
}
{
vDot(0) = control(0) - kStiffness * p(0) * p(0);
}
};
class LinearizedSystem :
public LinearSystem<state_dim, control_dim>
{
public:
state_control_matrix_t B_;
const double t = 0.0)
override {
return A_;
}
const double t = 0.0)
override {
B_ << 0, 1;
return B_;
}
LinearizedSystem* clone() const override { return new LinearizedSystem(); };
};
std::shared_ptr<CostFunctionQuadratic<state_dim, control_dim>>
createCostFunction(Eigen::Vector2d& x_final)
{
Eigen::Matrix2d Q;
Q << 0, 0, 0, 1;
Eigen::Matrix<double, 1, 1> R;
R << 100.0;
Eigen::Vector2d x_nominal = Eigen::Vector2d::Zero();
Eigen::Matrix<double, 1, 1> u_nominal = Eigen::Matrix<double, 1, 1>::Zero();
Eigen::Matrix2d Q_final;
Q_final << 10, 0, 0, 10;
std::shared_ptr<CostFunctionQuadratic<state_dim, control_dim>> quadraticCostFunction(
return quadraticCostFunction;
}
{
std::cout << "setting up problem " << std::endl;
Eigen::Vector2d x_final;
x_final << 2, 0;
gnms_settings.
K_sim = 50;
gnms_settings.
integrator =
ct::core::IntegrationType::EULER_SYM;
gnms_settings.
lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER;
shared_ptr<ControlledSystem<state_dim, control_dim>> nonlinearSystem(
new Dynamics);
shared_ptr<LinearSystem<state_dim, control_dim>> analyticLinearSystem(new LinearizedSystem);
shared_ptr<CostFunctionQuadratic<state_dim, control_dim>> costFunction =
createCostFunction(x_final);
size_t nSteps = std::round(tf / gnms_settings.
dt);
initState.setZero();
uff << kStiffness * initState(0) * initState(0);
for (
size_t i = 0;
i < nSteps + 1;
i++)
{
}
tf, x0[0], nonlinearSystem, costFunction, analyticLinearSystem);
size_t numIterations = 0;
while (numIterations < 50)
{
numIterations++;
}
}
}
}
}