|
class | BoxConstraintBase |
| Base for box constraint, templated on dimension of the decision vector of the derived class. More...
|
|
class | CARE |
| Continuous-Time Algebraic Riccati Equation. More...
|
|
class | Cholesky |
| Cholesky square root decomposition of a symmetric positive-definite matrix. More...
|
|
class | ConstraintBase |
| Base class for the constraints used in this toolbox. More...
|
|
class | ConstraintContainerAnalytical |
| Contains all the constraints using analytically calculated jacobians. More...
|
|
class | ConstraintContainerBase |
| The ConstraintBase Class is the base class for defining the non-linear optimization constraints. More...
|
|
class | ConstraintDiscretizer |
| The class takes continuous constraints defined with the constraint toolbox and discretizes them over the DMS shots. These discretized constraints can then be used in the NLP module. More...
|
|
class | ConstraintsContainerDms |
| Container class for the constraints used in DMS. More...
|
|
class | ContinuityConstraint |
| Implementation of the DMS continuity constraints. More...
|
|
class | ControlInputConstraint |
| Class for control input box constraint term. More...
|
|
class | ControllerDms |
| DMS controller class. More...
|
|
class | CostEvaluatorFull |
| Performs the full cost integration over the shots. More...
|
|
class | CostEvaluatorSimple |
| Evaluates the cost at the shots and performs some interpolation in between. More...
|
|
class | CostFunction |
| A base function for cost functions. All cost functions should derive from this. More...
|
|
class | CostFunctionAnalytical |
| A cost function which contains only terms that have analytical derivatives. More...
|
|
class | CostFunctionQuadratic |
| Describes a cost function with a quadratic approximation, i.e. one that can compute first and second order derivatives with respect to state and control input. This does NOT mean it has to be a purely quadratic cost function. If you are looking for a purely quadratic cost function, check CostFunctionQuadraticSimple. More...
|
|
class | CostFunctionQuadraticSimple |
| A simple quadratic cost function. More...
|
|
class | CTSystemModel |
| System model adapted to CT. System model encapsulates the integrator, so it is able to propagate the system, but also computes derivatives w.r.t. both state and noise. When propagating the system, CTSystemModel does not use the specified control input, but uses the assigned system controller instead. More...
|
|
class | DARE |
| Discrete-Time Algebraic Riccati Equation. More...
|
|
class | DisturbedSystem |
| Disturbed system augments the nominal system so that all the CT interfaces and dimensions are satisfied. What is done is basically augmenting the state with the assumed disturbance with specified dimensionality. More...
|
|
class | DisturbedSystemController |
| Disturbed controller allows us to augment the controller so that all the CT interfaces and dimensions are satisfied. Augmenting is done in such a way that the nominal controller is wrapped and all the nominal states are controlled in the same way as before augmenting the state. The augmented state (the disturbance part) is assumed constant, thus the computed derivates of that part of the state are set to zero. More...
|
|
class | DmsDimensions |
| Defines basic types used in the DMS algorithm. More...
|
|
struct | DmsPolicy |
| The DMS policy used as a solution container. More...
|
|
class | DmsProblem |
| This class sets up the DMS problem. More...
|
|
class | DmsSettings |
| Defines the DMS settings. More...
|
|
class | DmsSolver |
| Class to solve a specfic DMS problem. More...
|
|
class | DynamicRiccatiEquation |
| Dynamic Riccati Equation. More...
|
|
class | EstimatorBase |
| Estimator base. More...
|
|
class | ExtendedKalmanFilter |
| Extended Kalman Filter implementation. For an algorithmic overview, see also https://en.wikipedia.org/wiki/Extended_Kalman_filter. More...
|
|
struct | ExtendedKalmanFilterSettings |
| Settings for setting up an ExtendedKF. More...
|
|
class | FHDTLQR |
| Finite-Horizon Discrete Time LQR. More...
|
|
class | GNRiccatiSolver |
|
class | InitStateConstraint |
| The implementation of the DMS initial state constraint. More...
|
|
class | InputDisturbedSystem |
| Implementation of an input disturbed system where, the dimension of the disturbance is equal to the dimension of the control input, thus DIST_DIM = CONTROL_DIM. This is a special case, however it occurs often and is convenient to have as separate class. More...
|
|
class | IpoptSettings |
| IPOPT settings. Details about the parameters can be found in the IPOPT documentation. More...
|
|
class | LinearConstraintContainer |
| A base function for linear constraint functions which have a first derivative. More...
|
|
class | LinearMeasurementModel |
| Linear Measurement Model is an interface for linear measurement models most commonly used in practice. More...
|
|
class | LinearSpliner |
| The linear spline implementation. More...
|
|
struct | LineSearchSettings |
| GNMS Line Search Settings. More...
|
|
class | LQOCProblem |
| Defines a Linear-Quadratic Optimal Control Problem, which is optionally constrained. More...
|
|
class | LQOCSolver |
|
struct | LQOCSolverSettings |
| LQOC Solver settings. More...
|
|
class | LQR |
| continuous-time infinite-horizon LQR More...
|
|
class | LTIMeasurementModel |
| Linear Time-Invariant measurement model is simply a linear measurement model for which the matrix C is constant in time. More...
|
|
class | MeasurementModelBase |
|
class | MPC |
| Main MPC class. More...
|
|
struct | mpc_settings |
| MPC Settings struct. More...
|
|
class | MultipleShooting |
|
class | NLOCAlgorithm |
|
class | NLOCBackendBase |
| C++ implementation of GNMS. More...
|
|
class | NLOCBackendMP |
|
class | NLOCBackendST |
|
class | NLOptConSettings |
| Settings for the NLOptCon algorithm. More...
|
|
class | NLOptConSolver |
|
class | NlpSolverSettings |
| Contains the NLP solver settings. More...
|
|
class | ObstacleConstraint |
| Class for obstacle constraint. More...
|
|
class | OptconContinuousSystemInterface |
| interface class for optimal control algorithms More...
|
|
class | OptconDiscreteSystemInterface |
| interface class for optimal control algorithms More...
|
|
class | OptConProblemBase |
|
class | OptConSolver |
|
class | OptconSystemInterface |
| interface base class for optimal control algorithms More...
|
|
class | OptVectorDms |
| This class is a wrapper around the NLP Optvector. It wraps the Vectors from the NLP solvers into state, control and time trajectories. More...
|
|
class | PolicyHandler |
|
class | RKnDerivatives |
| This class implements analytical sensitivity generation for the euler and rk4 integration scheme. More...
|
|
class | SensitivityIntegratorCT |
| This class can integrate a controlled system and a costfunction. Furthermore, it provides first order derivatives with respect to initial state and control. More...
|
|
class | ShotContainer |
| This class performs the state and the sensitivity integration on a shot. More...
|
|
class | SingleShooting |
|
class | SnoptSettings |
| SnoptSolver settings. Details about the parameters can be found in the SNOPT documentation. More...
|
|
class | SnoptSolver |
|
class | SplinerBase |
| Abstract base class for the control input splining between the DMS shots. More...
|
|
class | StateConstraint |
| Class for state box constraint. More...
|
|
class | StateFeedbackPolicyHandler |
| the default policy handler for iLQR More...
|
|
struct | StateObserverSettings |
| Settings for setting up a StateObserver. More...
|
|
class | SteadyStateKalmanFilter |
| Steady State Kalman Filter is a time invariant linear estimator. It starts with the same update rule as the standard Kalman Filter, but instead of propagating the covariance and estimate through time, it assumes convergence reducing the problem to solving an Algebraic Ricatti Equation. More...
|
|
struct | SteadyStateKalmanFilterSettings |
| Settings for setting up a SteadyStateKF. More...
|
|
class | SwitchedLinearConstraintContainer |
| A container for switching linear constraint containers. More...
|
|
class | SystemModelBase |
| System model is an interface that encapsulates the integrator to be able to propagate the system, but is also able to compute derivatives w.r.t. both state and noise. More...
|
|
class | TermBase |
| An interface for a term, supporting both analytical and auto-diff terms. More...
|
|
class | TerminalConstraint |
| Class for terminal constraint. More...
|
|
class | TermLinear |
| A linear term of type . More...
|
|
class | TermMixed |
| A basic quadratic term of type . More...
|
|
class | TermQuadMult |
| A multiplicative term of type . More...
|
|
class | TermQuadratic |
| A basic quadratic term of type . More...
|
|
class | TermQuadTracking |
| A quadratic tracking term of type . More...
|
|
class | TermSmoothAbs |
| A smooth absolute term of type where this calculation is performed component-wise and summed with individual weighting factors a[i], b[i]. More...
|
|
class | TermStateBarrier |
| A state barrier term (could also be considered a soft constraint) Note that this term explicitly excludes controls, as there are better ways to limit control effort in a "soft" way, e.g. through the use of sigmoid functions. More...
|
|
class | UnscentedKalmanFilter |
| Unscented Kalman Filter is a nonlinear estimator best suited for highly nonlinear systems. It combines the principles of EKF and particle filter. The downside is the computation complexity. More...
|
|
struct | UnscentedKalmanFilterSettings |
| Settings for setting up an UnscentedKF. More...
|
|
class | ZeroOrderHoldSpliner |
| The spline implementation for the zero order hold spliner. More...
|
|
|
template<typename SCALAR > |
void | loadScalarCF (const std::string &filename, const std::string &scalarName, SCALAR &scalar, const std::string &termName="") |
|
template<typename SCALAR > |
void | loadScalarOptionalCF (const std::string &filename, const std::string &scalarName, SCALAR &scalar, const std::string &termName, const SCALAR &defaultValue) |
|
template<typename SCALAR , int ROW, int COL> |
void | loadMatrixCF (const std::string &filename, const std::string &matrixName, Eigen::Matrix< SCALAR, ROW, COL > &matrix, const std::string &termName="") |
|
template<typename TERM_PTR , typename costFuncType > |
void | addTerm (const std::string &filename, std::string ¤tTerm, int currentTermType, TERM_PTR term, costFuncType *costFunc, bool verbose=false) |
|
template<typename TERM_PTR , typename costFuncType > |
void | addADTerm (const std::string &filename, std::string ¤tTerm, int currentTermType, TERM_PTR term, costFuncType *costFunc, bool verbose=false) |
|
void | loadMpcSettings (const std::string &filename, mpc_settings &settings) |
| load the mpc settings from file More...
|
|