This example shows how to use general constraints alongside NLOC and requires HPIPM to be installed The unconstrained Riccati backward-pass is replaced by a high-performance interior-point constrained linear-quadratic Optimal Control solver.
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
{
Base::lb_.resize(1);
Base::ub_.resize(1);
Base::lb_.setConstant(-1.0);
Base::ub_.setConstant(1.0);
}
virtual size_t getConstraintSize() const override { return 1; }
virtual Eigen::VectorXd evaluate(
const state_vector_t&
x,
const control_vector_t&
u,
const double t)
override {
Eigen::Matrix<double, 1, 1> val;
val.template segment<1>(0) <<
u(0) *
x(0) *
x(0);
return val;
}
virtual Eigen::Matrix<ct::core::ADCGScalar, Eigen::Dynamic, 1> evaluateCppadCg(
ct::core::ADCGScalar t) override
{
Eigen::Matrix<ct::core::ADCGScalar, 1, 1> val;
val.template segment<1>(0) <<
u(0) *
x(0) *
x(0);
return val;
}
};
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 + "/nlocCost.info", "intermediateCost", verbose);
finalCost->loadConfigFile(ct::optcon::exampleDir + "/nlocCost.info", "finalCost", verbose);
std::shared_ptr<CostFunctionQuadratic<state_dim, control_dim>> costFunction(
costFunction->addIntermediateTerm(intermediateCost);
costFunction->addFinalTerm(finalCost);
std::shared_ptr<ct::optcon::ConstraintContainerAD<state_dim, control_dim>> generalConstraints(
new ct::optcon::ConstraintContainerAD<state_dim, control_dim>());
generalConstraints->addIntermediateConstraint(pathConstraintTerm, verbose);
generalConstraints->addTerminalConstraint(pathConstraintTerm, verbose);
generalConstraints->initialize();
x0.setZero();
timeHorizon, x0, oscillatorDynamics, costFunction, adLinearizer);
nloc_settings.
load(ct::optcon::exampleDir +
"/nlocSolver.info",
true,
"ilqr");
nloc_settings.
lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER;
size_t K = nloc_settings.
computeK(timeHorizon);
plotResultsOscillator<state_dim, control_dim>(solution.
x_ref(), solution.
uff(), solution.
time());
}