Classes | |
class | AdjointERKExport |
Allows to export a tailored explicit Runge-Kutta integrator with adjoint first order sensitivity propagation for fast model predictive control. More... | |
class | AdjointLiftedIRKExport |
Allows to export a tailored lifted implicit Runge-Kutta integrator with adjoint sensitivity generation for extra fast model predictive control. More... | |
class | BFGSupdate |
Implements BFGS updates for approximating second-order derivatives within NLPsolvers. More... | |
class | CollocationMethod |
Discretizes a DifferentialEquation by means of a collocation scheme. More... | |
class | ConjugateGradientMethod |
Implements a conjugate gradient method as sparse linear algebra solver. More... | |
class | ConstantHessian |
Implements a constant Hessian as approximation of second-order derivatives within NLPsolvers. More... | |
class | DiagonallyImplicitRKExport |
Allows to export a tailored diagonally implicit Runge-Kutta integrator for fast model predictive control. More... | |
class | DiagonallyIRK3Export |
Allows to export a tailored diagonally implicit 2-stage Runge-Kutta method of order 3 for fast model predictive control. More... | |
class | DiagonallyIRK4Export |
Allows to export a tailored diagonally implicit 3-stage Runge-Kutta method of order 4 for fast model predictive control. More... | |
class | DiagonallyIRK5Export |
Allows to export a tailored diagonally implicit 5-stage Runge-Kutta method of order 5 for fast model predictive control. More... | |
class | DiscreteTimeExport |
Allows to export a tailored discrete-time 'integrator' for fast model predictive control. More... | |
class | DynamicDiscretization |
Base class for discretizing a DifferentialEquation for use in optimal control algorithms. More... | |
class | ExactHessian |
Implements an exact Hessian computation for obtaining second-order derivatives within NLPsolvers. More... | |
class | ExplicitEulerExport |
Allows to export a tailored explicit Euler method for fast model predictive control. More... | |
class | ExplicitRungeKutta2Export |
Allows to export a tailored explicit Runge-Kutta integrator of order 2 for fast model predictive control. More... | |
class | ExplicitRungeKutta3Export |
Allows to export a tailored explicit Runge-Kutta integrator of order 3 for fast model predictive control. More... | |
class | ExplicitRungeKutta4Export |
Allows to export a tailored explicit Runge-Kutta integrator of order 4 for fast model predictive control. More... | |
class | ExplicitRungeKuttaExport |
Allows to export a tailored explicit Runge-Kutta integrator for fast model predictive control. More... | |
class | ExportAlgorithm |
Allows to export automatically generated algorithms for fast model predictive control. More... | |
class | ExportCholeskyDecomposition |
A class for exporting a function for calculation of the Cholesky decomposition. More... | |
class | ExportCholeskySolver |
Allows to export linear solver based on Cholesky factorization. More... | |
class | ExportExactHessianCN2 |
TBD. More... | |
class | ExportExactHessianQpDunes |
A class for export of an OCP solver using sparse QP solver qpDUNES. More... | |
class | ExportFile |
Allows to export files containing automatically generated algorithms for fast model predictive control. More... | |
class | ExportGaussElim |
Allows to export Gaussian elimination for solving linear systems of specific dimensions. More... | |
class | ExportGaussNewtonBlockCN2 |
An OCP solver based on the block N^2 condensing algorithm. More... | |
class | ExportGaussNewtonBlockForces |
An OCP solver based on the block N^2 condensing algorithm, in combination with qpDUNES as the QP solver. More... | |
class | ExportGaussNewtonBlockQpDunes |
An OCP solver based on the block N^2 condensing algorithm, in combination with qpDUNES as the QP solver. More... | |
class | ExportGaussNewtonCN2 |
An OCP solver based on the N^2 condensing algorithm. More... | |
class | ExportGaussNewtonCn2Factorization |
TBD. More... | |
class | ExportGaussNewtonCondensed |
A class for export of Gauss-Newton condensed OCP solver. More... | |
class | ExportGaussNewtonForces |
A class for export of an OCP solver using sparse QP solver FORCES. More... | |
class | ExportGaussNewtonGeneric |
TBD. More... | |
class | ExportGaussNewtonHpmpc |
TBD. More... | |
class | ExportGaussNewtonQpDunes |
A class for export of an OCP solver using sparse QP solver qpDUNES. More... | |
class | ExportHouseholderQR |
Allows to export Householder QR Factorization for solving linear systems of specific dimensions. More... | |
class | ExportIRK3StageSimplifiedNewton |
Allows to export a tailored IRK solver based on Gaussian elimination of specific dimensions. More... | |
class | ExportIRK3StageSingleNewton |
Allows to export a tailored IRK solver based on Gaussian elimination of specific dimensions. More... | |
class | ExportIRK4StageSimplifiedNewton |
Allows to export a tailored IRK solver based on Gaussian elimination of specific dimensions. More... | |
class | ExportIRK4StageSingleNewton |
Allows to export a tailored IRK solver based on Gaussian elimination of specific dimensions. More... | |
class | ExportLinearSolver |
Allows to export automatically generated algorithms for solving linear systems of specific dimensions. More... | |
class | ExportNLPSolver |
Base class for export of NLP/OCP solvers. More... | |
class | FeedbackLiftedIRKExport |
Allows to export a tailored lifted implicit Runge-Kutta integrator with forward sensitivity generation for extra fast model predictive control. More... | |
class | ForwardBackwardLiftedIRKExport |
Allows to export a tailored lifted implicit Runge-Kutta integrator with forward-over-adjoint second order sensitivity generation for extra fast model predictive control. More... | |
class | ForwardIRKExport |
Allows to export a tailored implicit Runge-Kutta integrator with forward sensitivity generation for fast model predictive control. More... | |
class | ForwardLiftedIRKExport |
Allows to export a tailored lifted implicit Runge-Kutta integrator with forward sensitivity generation for extra fast model predictive control. More... | |
class | ForwardOverBackwardERKExport |
Allows to export a tailored explicit Runge-Kutta integrator with forward-over-backward second order sensitivity propagation for fast model predictive control. More... | |
class | GaussLegendre2Export |
Allows to export a tailored Gauss-Legendre method of order 2 for fast model predictive control. More... | |
class | GaussLegendre4Export |
Allows to export a tailored Gauss-Legendre method of order 4 for fast model predictive control. More... | |
class | GaussLegendre6Export |
Allows to export a tailored Gauss-Legendre method of order 6 for fast model predictive control. More... | |
class | GaussLegendre8Export |
Allows to export a tailored Gauss-Legendre method of order 8 for fast model predictive control. More... | |
class | GaussNewtonApproximation |
Implements a Gauss-Newton approximation as second-order derivatives within NLPsolvers. More... | |
class | GaussNewtonApproximationWithBFGS |
Implements a Gauss-Newton approximation with block BFGS updates as second-order derivatives within NLPsolvers. More... | |
class | ImplicitRungeKuttaExport |
Allows to export a tailored implicit Runge-Kutta integrator for fast model predictive control. More... | |
class | IntegratorBDF |
Implements the backward-differentiation formula for integrating DAEs. More... | |
class | IntegratorDiscretizedODE |
Implements a scheme for evaluating discretized ODEs. More... | |
class | IntegratorExport |
Allows to export a tailored integrator for fast model predictive control. More... | |
class | IntegratorLYAPUNOV |
Base class for all kinds of Runge-Kutta schemes for integrating ODEs. More... | |
class | IntegratorLYAPUNOV45 |
Implements the Runge-Kutta-45 scheme for integrating ODEs. More... | |
class | IntegratorRK |
Abstract base class for all kinds of Runge-Kutta schemes for integrating ODEs. More... | |
class | IntegratorRK12 |
Implements the Runge-Kutta-12 scheme for integrating ODEs. More... | |
class | IntegratorRK23 |
Implements the Runge-Kutta-23 scheme for integrating ODEs. More... | |
class | IntegratorRK45 |
Implements the Runge-Kutta-45 scheme for integrating ODEs. More... | |
class | IntegratorRK78 |
Implements the Runge-Kutta-78 scheme for integrating ODEs. More... | |
class | IPmethod |
Implements different interior-point methods for solving NLPs. More... | |
class | LiftedERKExport |
Allows to export a tailored explicit Runge-Kutta integrator with a lifted Newton method to efficiently support (implicit) DAE systems for fast model predictive control. More... | |
class | NARXExport |
Allows to export a tailored polynomial NARX integrator for fast model predictive control. More... | |
class | NormalConjugateGradientMethod |
Implements a conjugate gradient method as sparse linear algebra solver for non-symmetric linear systems. More... | |
class | RadauIIA1Export |
Allows to export a tailored Radau IIA method of order 1 for fast model predictive control. More... | |
class | RadauIIA3Export |
Allows to export a tailored Radau IIA method of order 3 for fast model predictive control. More... | |
class | RadauIIA5Export |
Allows to export a tailored Radau IIA method of order 5 for fast model predictive control. More... | |
class | RKSensitivitiesExport |
Allows to export a tailored Runge-Kutta sensitivity propagation for fast model predictive control. More... | |
class | RungeKuttaExport |
Allows to export a tailored Runge-Kutta integrator for fast model predictive control. More... | |
class | SCPevaluation |
Base class for different ways to evaluate functions and derivatives within an SCPmethod for solving NLPs. More... | |
class | SCPmeritFunction |
Allows to evaluate a merit function within an SCPmethod for solving NLPs. More... | |
class | SCPmethod |
Implements different sequential convex programming methods for solving NLPs. More... | |
class | SCPstep |
Base class for different ways to perform a step of an SCPmethod for solving NLPs. More... | |
class | SCPstepFullstep |
Implements a fullstep to perform a step of an SCPmethod for solving NLPs. More... | |
class | SCPstepLinesearch |
Implements linesearch techniques to perform a globalized step of an SCPmethod for solving NLPs. More... | |
class | ShootingMethod |
Discretizes a DifferentialEquation by means of single or multiple shooting. More... | |
class | SymmetricConjugateGradientMethod |
Implements a conjugate gradient method as sparse linear algebra solver for symmetric linear systems. More... | |
class | SymmetricIRKExport |
Allows to export a tailored implicit Runge-Kutta integrator with symmetric second order sensitivity generation for extra fast model predictive control. More... | |
class | SymmetricLiftedIRKExport |
Allows to export a tailored lifted implicit Runge-Kutta integrator with symmetric second order sensitivity generation for extra fast model predictive control. More... | |
class | ThreeSweepsERKExport |
Allows to export a tailored explicit Runge-Kutta integrator with three-sweeps second order sensitivity propagation for fast model predictive control. More... | |