- 3.0.2 core module.
ct::core Namespace Reference

Namespaces

 ADHelperFunctions
 
 generated
 
 internal
 
 inverseHelperfunctions
 
 plot
 
 plotQwt
 
 tpl
 

Classes

class  ADHelpers
 
class  ConstantController
 A constant controller. More...
 
class  ConstantStateFeedbackController
 A constant state feedback controller. More...
 
class  ConstantTrajectoryController
 A constant controller. More...
 
class  ControlledSystem
 A general, non-linear dynamic system with a control input. More...
 
class  Controller
 Interface class for all controllers. More...
 
class  ControlMatrix
 
class  ControlSimulator
 A class for simulating controlled systems in a general way. More...
 
class  ControlVector
 
class  Derivatives
 General interface class for a Derivatives. More...
 
class  DerivativesCppadSettings
 Contains the NLP solver settings. More...
 
class  DerivativesNumDiff
 Derivatives using Num-Diff Codegeneration. More...
 
class  DiscreteArray
 An discrete array (vector) of a particular data type. More...
 
class  DiscreteControlledSystem
 A general, non-linear discrete dynamic system with a control input. More...
 
class  DiscreteController
 Interface class for all controllers. More...
 
class  DiscreteLinearSystem
 interface class for a general discrete linear system or linearized discrete system More...
 
class  DiscreteSystem
 
class  DiscreteSystemLinearizer
 Computes the linearization of a general non-linear DiscreteControlledSystem using numerical differentiation. More...
 
class  DiscreteTrajectoryBase
 A discrete, timed trajectory with interpolation. More...
 
class  DynamicsLinearizerNumDiff
 Computes the linearization of a system dynamics function through numerical finite differencing. More...
 
class  EventHandler
 Interface for an event handler for an Integrator. More...
 
class  FeedbackMatrix
 
class  GaussianNoise
 Gaussian noise generator. More...
 
class  GeneralLinearFunction
 
class  Integrator
 Standard Integrator. More...
 
class  IntegratorSymplectic
 This class wraps the symplectic integrators from boost to this toolbox. More...
 
class  Interpolation
 Class that performs interpolation of data in time. More...
 
class  KillIntegrationEventHandler
 Event handler to kill integration. More...
 
class  LinearFunctionMIMO
 
class  LinearSystem
 interface class for a general linear system or linearized system More...
 
class  LTISystem
 Linear time-invariant system. More...
 
class  MaxStepsEventHandler
 Event handler to kill a (variable step) Integrator after doing too many steps. More...
 
class  Observer
 Observer for Integrator. More...
 
class  OutputMatrix
 
class  OutputStateMatrix
 
class  OutputVector
 
class  PhaseSequence
 Describes a Phase sequence with timing. More...
 
class  PIDController
 A standard PIDController. More...
 
class  Plane
 Implements a geometrical 3D plane of type $ ax + by + cz = d $. More...
 
class  PlaneEstimator
 Estimates a Plane from a number of 3D points using least squares. More...
 
class  QuantizationNoise
 Quantization of data. More...
 
class  ScalarArray
 An array of scalar data types. More...
 
class  ScalarTrajectory
 Specialized type of a discrete trajectory for scalar types. More...
 
class  Sensitivity
 
class  SensitivityApproximation
 interface class for a general linear system or linearized system More...
 
struct  SensitivityApproximationSettings
 settings for the SensitivityApproximation More...
 
class  SensitivityIntegrator
 This class can integrate a controlled system Furthermore, it provides first order derivatives with respect to initial state and control. More...
 
class  StateControlMatrix
 
class  StateFeedbackController
 A linear state feedback controller. More...
 
class  StateMatrix
 
class  StateVector
 
class  StepInputController
 A simple step input. More...
 
class  SubstepRecorder
 Event handler to record substeps. More...
 
class  SwitchedControlledSystem
 A general, switched non-linear dynamic system with a control input. More...
 
class  SwitchedDiscreteControlledSystem
 A general, switched non-linear discrete dynamic system with a control input. More...
 
class  SwitchedDiscreteLinearSystem
 class for a general switched discrete linear system or linearized discrete system More...
 
class  SwitchedLinearSystem
 interface class for a general switched linear system or linearized system More...
 
struct  SwitchEvent
 Describes a switch between phases. More...
 
class  SymplecticSystem
 The base class for the implementation of a symplectic system. In a symplectic system, the position and the velocity update can be separated. During integration, the velocity gets update first and the position update uses the updated velocity. More...
 
class  System
 Interface class for a general system described by an ordinary differential equation (ODE) More...
 
class  SystemDiscretizer
 Discretize a general, continuous-time non-linear dynamic system using forward integration. More...
 
class  SystemLinearizer
 Computes the linearization of a general non-linear ControlledSystem using numerical differentiation. More...
 
class  TrajectoryBase
 Basic interface class for a trajectory. More...
 
class  UniformNoise
 Uniform noise generator. More...
 

Typedefs

typedef tpl::TestLinearSystem< double > TestLinearSystem
 
typedef tpl::ActivationBase< double > ActivationBase
 
typedef tpl::BarrierActivation< double, ct::core::internal::DoubleTraitBarrierActivation
 
typedef tpl::LinearActivation< double > LinearActivation
 
typedef tpl::PeriodicActivation< double > PeriodicActivation
 
typedef tpl::RBFGaussActivation< double > RBFGaussActivation
 
typedef tpl::SingleActivation< double > SingleActivation
 
typedef tpl::ExternallyDrivenTimer< double > ExternallyDrivenTimer
 
typedef tpl::Timer< double > Timer
 
typedef tpl::Ellipsoid< double > Ellipsoid
 
template<size_t POS_DIM, size_t VEL_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using IntegratorSymplecticEuler = IntegratorSymplectic< POS_DIM, VEL_DIM, CONTROL_DIM, internal::symplectic_euler_t< POS_DIM, VEL_DIM, SCALAR >, SCALAR >
 
template<size_t POS_DIM, size_t VEL_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using IntegratorSymplecticRk = IntegratorSymplectic< POS_DIM, VEL_DIM, CONTROL_DIM, internal::symplectic_rk_t< POS_DIM, VEL_DIM, SCALAR >, SCALAR >
 
template<class T , class Alloc = Eigen::aligned_allocator<T>>
using Switched = std::vector< T, Alloc >
 Declaring Switched alias such that we can write Switched<System> More...
 
using ContinuousModeSequence = PhaseSequence< std::size_t, double >
 
using ContinuousModeSwitch = SwitchEvent< std::size_t, double >
 
using DiscreteModeSequence = PhaseSequence< std::size_t, int >
 
using DiscreteModeSwitch = SwitchEvent< std::size_t, int >
 
typedef tpl::SecondOrderSystem< double > SecondOrderSystem
 harmonic oscillator (double) More...
 
template<size_t CONTROL_DIM, typename SCALAR = double>
using ControlMatrixArray = DiscreteArray< ControlMatrix< CONTROL_DIM, SCALAR > >
 
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using FeedbackArray = DiscreteArray< FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > >
 
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using StateControlMatrixArray = DiscreteArray< StateControlMatrix< STATE_DIM, CONTROL_DIM, SCALAR > >
 
template<size_t STATE_DIM, typename SCALAR = double>
using StateMatrixArray = DiscreteArray< StateMatrix< STATE_DIM, SCALAR > >
 
template<size_t STATE_DIM, typename SCALAR = double>
using StateVectorArray = DiscreteArray< StateVector< STATE_DIM, SCALAR > >
 
template<size_t CONTROL_DIM, typename SCALAR = double>
using ControlVectorArray = DiscreteArray< ControlVector< CONTROL_DIM, SCALAR > >
 
template<size_t OUTPUT_DIM, typename SCALAR = double>
using OutputVectorArray = DiscreteArray< OutputVector< OUTPUT_DIM, SCALAR > >
 
template<size_t OUTPUT_DIM, typename SCALAR = double>
using OutputMatrixArray = DiscreteArray< OutputMatrix< OUTPUT_DIM, SCALAR > >
 
typedef tpl::TimeArray< double > TimeArray
 
typedef double Time
 
template<size_t CONTROL_DIM, typename SCALAR = double, typename TIME_SCALAR = SCALAR>
using ControlTrajectory = DiscreteTrajectoryBase< ControlVector< CONTROL_DIM, SCALAR >, Eigen::aligned_allocator< ControlVector< CONTROL_DIM, SCALAR > >, TIME_SCALAR >
 
template<size_t CONTROL_DIM, typename SCALAR = double>
using ControlMatrixTrajectory = DiscreteTrajectoryBase< ControlMatrix< CONTROL_DIM, SCALAR > >
 
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using FeedbackTrajectory = DiscreteTrajectoryBase< FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR >, Eigen::aligned_allocator< FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR > >, SCALAR >
 
template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using StateControlMatrixTrajectory = DiscreteTrajectoryBase< StateControlMatrix< STATE_DIM, CONTROL_DIM, SCALAR > >
 
template<size_t STATE_DIM, typename SCALAR = double>
using StateMatrixTrajectory = DiscreteTrajectoryBase< StateMatrix< STATE_DIM, SCALAR > >
 
template<size_t STATE_DIM, typename SCALAR = double, typename TIME_SCALAR = SCALAR>
using StateTrajectory = DiscreteTrajectoryBase< StateVector< STATE_DIM, SCALAR >, Eigen::aligned_allocator< StateVector< STATE_DIM, SCALAR > >, TIME_SCALAR >
 
typedef tpl::TestDiscreteNonlinearSystem< double > TestDiscreteNonlinearSystem
 
typedef tpl::TestNonlinearSystem< double > TestNonlinearSystem
 
typedef tpl::TestSymplecticSystem< double > TestSymplecticSystem
 

Enumerations

enum  InterpolationType { ZOH = 0, LIN }
 
enum  IntegrationType {
  EULER, RK4, MODIFIED_MIDPOINT, ODE45,
  RK5VARIABLE, RK78, BULIRSCHSTOER, EULERCT,
  RK4CT, EULER_SYM, RK_SYM
}
 The available integration types. More...
 
enum  SYSTEM_TYPE { GENERAL = 0, SECOND_ORDER }
 type of system More...
 

Functions

template<typename SCALAR >
void loadScalar (const std::string &filename, const std::string &scalarName, SCALAR &scalar, const std::string &ns="")
 Loads a scalar file from an .info file. More...
 
template<typename SCALAR >
void loadScalarOptional (const std::string &filename, const std::string &scalarName, SCALAR &scalar, const SCALAR &defaultValue, const std::string &ns="")
 Tries to load a scalar from an .info file. Falls back to default value if not found. More...
 
template<typename SCALAR , int ROW, int COL>
void loadMatrix (const std::string &filename, const std::string &matrixName, Eigen::Matrix< SCALAR, ROW, COL > &matrix, const std::string &ns="")
 Loads a matrix/vector file from an .info file. More...
 
template<typename TRAJECTORY_T >
TRAJECTORY_T linspace (const typename TRAJECTORY_T::value_type &a, const typename TRAJECTORY_T::value_type &b, const size_t N)
 replicates the well-known linspace command from MATLAB in C++ More...
 
template<typename SCALAR >
Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > LUsolve (const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &A, const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &B)
 
template<typename SCALAR >
Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > LDLTsolve (const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &A, const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &B)
 
template<typename EIGEN_VECTOR_ARRAY_TYPE_IN , typename SCALAR = double>
DiscreteArray< Eigen::Matrix< SCALAR, -1, -1 > > transposeArray (const EIGEN_VECTOR_ARRAY_TYPE_IN &array)
 this method transposes/flips an array of vectors into another array containing the scalar trajectories corresponding to each dimension of the input array. More...
 

Typedef Documentation

◆ ActivationBase

◆ BarrierActivation

◆ LinearActivation

◆ PeriodicActivation

◆ RBFGaussActivation

◆ SingleActivation

◆ ExternallyDrivenTimer

◆ Timer

typedef tpl::Timer<double> ct::core::Timer

◆ Ellipsoid

◆ IntegratorSymplecticEuler

template<size_t POS_DIM, size_t VEL_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::IntegratorSymplecticEuler = typedef IntegratorSymplectic<POS_DIM, VEL_DIM, CONTROL_DIM, internal::symplectic_euler_t<POS_DIM, VEL_DIM, SCALAR>, SCALAR>

◆ IntegratorSymplecticRk

template<size_t POS_DIM, size_t VEL_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::IntegratorSymplecticRk = typedef IntegratorSymplectic<POS_DIM, VEL_DIM, CONTROL_DIM, internal::symplectic_rk_t<POS_DIM, VEL_DIM, SCALAR>, SCALAR>

◆ Switched

template<class T , class Alloc = Eigen::aligned_allocator<T>>
using ct::core::Switched = typedef std::vector<T, Alloc>

Declaring Switched alias such that we can write Switched<System>

◆ ContinuousModeSequence

using ct::core::ContinuousModeSequence = typedef PhaseSequence<std::size_t, double>

◆ ContinuousModeSwitch

using ct::core::ContinuousModeSwitch = typedef SwitchEvent<std::size_t, double>

◆ DiscreteModeSequence

using ct::core::DiscreteModeSequence = typedef PhaseSequence<std::size_t, int>

◆ DiscreteModeSwitch

using ct::core::DiscreteModeSwitch = typedef SwitchEvent<std::size_t, int>

◆ SecondOrderSystem

harmonic oscillator (double)

Examples:
SecondOrderSystemTest.cpp.

◆ ControlMatrixArray

template<size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::ControlMatrixArray = typedef DiscreteArray<ControlMatrix<CONTROL_DIM, SCALAR> >

◆ FeedbackArray

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::FeedbackArray = typedef DiscreteArray<FeedbackMatrix<STATE_DIM, CONTROL_DIM, SCALAR> >

◆ StateControlMatrixArray

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::StateControlMatrixArray = typedef DiscreteArray<StateControlMatrix<STATE_DIM, CONTROL_DIM, SCALAR> >

◆ StateMatrixArray

template<size_t STATE_DIM, typename SCALAR = double>
using ct::core::StateMatrixArray = typedef DiscreteArray<StateMatrix<STATE_DIM, SCALAR> >

◆ StateVectorArray

template<size_t STATE_DIM, typename SCALAR = double>
using ct::core::StateVectorArray = typedef DiscreteArray<StateVector<STATE_DIM, SCALAR> >

◆ ControlVectorArray

template<size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::ControlVectorArray = typedef DiscreteArray<ControlVector<CONTROL_DIM, SCALAR> >

◆ OutputVectorArray

template<size_t OUTPUT_DIM, typename SCALAR = double>
using ct::core::OutputVectorArray = typedef DiscreteArray<OutputVector<OUTPUT_DIM, SCALAR> >

◆ OutputMatrixArray

template<size_t OUTPUT_DIM, typename SCALAR = double>
using ct::core::OutputMatrixArray = typedef DiscreteArray<OutputMatrix<OUTPUT_DIM, SCALAR> >

◆ TimeArray

◆ Time

typedef double ct::core::Time

◆ ControlTrajectory

template<size_t CONTROL_DIM, typename SCALAR = double, typename TIME_SCALAR = SCALAR>
using ct::core::ControlTrajectory = typedef DiscreteTrajectoryBase<ControlVector<CONTROL_DIM, SCALAR>, Eigen::aligned_allocator<ControlVector<CONTROL_DIM, SCALAR> >, TIME_SCALAR>

◆ ControlMatrixTrajectory

template<size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::ControlMatrixTrajectory = typedef DiscreteTrajectoryBase<ControlMatrix<CONTROL_DIM, SCALAR> >

◆ FeedbackTrajectory

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::FeedbackTrajectory = typedef DiscreteTrajectoryBase<FeedbackMatrix<STATE_DIM, CONTROL_DIM, SCALAR>, Eigen::aligned_allocator<FeedbackMatrix<STATE_DIM, CONTROL_DIM, SCALAR> >, SCALAR>

◆ StateControlMatrixTrajectory

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
using ct::core::StateControlMatrixTrajectory = typedef DiscreteTrajectoryBase<StateControlMatrix<STATE_DIM, CONTROL_DIM, SCALAR> >

◆ StateMatrixTrajectory

template<size_t STATE_DIM, typename SCALAR = double>
using ct::core::StateMatrixTrajectory = typedef DiscreteTrajectoryBase<StateMatrix<STATE_DIM, SCALAR> >

◆ StateTrajectory

template<size_t STATE_DIM, typename SCALAR = double, typename TIME_SCALAR = SCALAR>
using ct::core::StateTrajectory = typedef DiscreteTrajectoryBase<StateVector<STATE_DIM, SCALAR>, Eigen::aligned_allocator<StateVector<STATE_DIM, SCALAR> >, TIME_SCALAR>

◆ TestDiscreteNonlinearSystem

◆ TestNonlinearSystem

◆ TestSymplecticSystem

Enumeration Type Documentation

◆ InterpolationType

Enumerator
ZOH 

Zero-Order hold.

LIN 

LIN.

◆ IntegrationType

The available integration types.

Enumerator
EULER 
RK4 
MODIFIED_MIDPOINT 
ODE45 
RK5VARIABLE 
RK78 
BULIRSCHSTOER 
EULERCT 
RK4CT 
EULER_SYM 
RK_SYM 

◆ SYSTEM_TYPE

type of system

Enumerator
GENERAL 

any non-specific system

SECOND_ORDER 

a pure second-order system

Function Documentation

◆ loadScalar()

template<typename SCALAR >
void ct::core::loadScalar ( const std::string &  filename,
const std::string &  scalarName,
SCALAR scalar,
const std::string &  ns = "" 
)

Loads a scalar file from an .info file.

Warning
This function will throw an exception if the scalar is not found. For a non-throwing version, see loadScalarOptional()
Parameters
filenamethe full or relative path of the file to load
scalarNamethe name of the scalar in the info file
scalarvalue to store
nsthe namespace that the scalar lives in
Template Parameters
SCALARthe scalar type, i.e. double, int, size_t etc.

◆ loadScalarOptional()

template<typename SCALAR >
void ct::core::loadScalarOptional ( const std::string &  filename,
const std::string &  scalarName,
SCALAR scalar,
const SCALAR defaultValue,
const std::string &  ns = "" 
)

Tries to load a scalar from an .info file. Falls back to default value if not found.

Parameters
filenamethe full or relative path of the file to load
scalarNamethe name of the scalar in the info file
scalarvalue to store
defaultValuethe default value to fall back to. Can be the same as scalar.
nsthe namespace that the scalar lives in
Template Parameters
SCALARthe scalar type, i.e. double, int, size_t etc.

◆ loadMatrix()

template<typename SCALAR , int ROW, int COL>
void ct::core::loadMatrix ( const std::string &  filename,
const std::string &  matrixName,
Eigen::Matrix< SCALAR, ROW, COL > &  matrix,
const std::string &  ns = "" 
)

Loads a matrix/vector file from an .info file.

This function supports sparse storage of vectors matrices, i.e. all entries not found in the .info file are assumed to be zero. Also, it looks for a parameter called "scaling" (defaults to 1) and multiplies all stored values. The example file:

  • M
    {
    scaling 2.5
    (0,0) 10.0
    (1,1) 20.0
    (2,2) 0.0
    (2,0) 1.0
    }

would generate the following matrix

\[ M = 2.5 \cdot \begin{pmatrix} 10 & 0.0 & 0.0 \\ 0.0 & 2.0 & 0.0 \\ 1.0 & 0.0 & 0.0 \end{pmatrix} = \begin{pmatrix} 25 & 0.0 & 0.0 \\ 0.0 & 50.0 & 0.0 \\ 25.0 & 0.0 & 0.0 \end{pmatrix} \]

Warning
If the matrix is not found, it defaults all entries to zero.
Parameters
filenamethe full or relative path of the file to load
matrixNamethe name of the matrix in the info file
matrixvalue to store
nsthe namespace that the matrix lives in
Template Parameters
SCALARthe scalar type, i.e. double, int, size_t etc.
ROWnumber of rows (needs to be positive!)
COLnumer of columns (needs to be positive!)

References i.

◆ linspace()

template<typename TRAJECTORY_T >
TRAJECTORY_T ct::core::linspace ( const typename TRAJECTORY_T::value_type &  a,
const typename TRAJECTORY_T::value_type &  b,
const size_t  N 
)

replicates the well-known linspace command from MATLAB in C++

linspace provides exactly the same properties and functionality like in MATLAB.

  • N denotes the number of points, so you will obtain N-1 intervals
  • a is the start of the interval
  • b is the end of the interval

Unit test LinspaceTest.cpp illustrates the use of linspace.

Examples:
DiscreteTrajectoryTest.cpp.

Referenced by TEST().

◆ LUsolve()

template<typename SCALAR >
Eigen::Matrix<SCALAR, Eigen::Dynamic, Eigen::Dynamic> ct::core::LUsolve ( const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &  A,
const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &  B 
)

References n, and X.

◆ LDLTsolve()

template<typename SCALAR >
Eigen::Matrix<SCALAR, Eigen::Dynamic, Eigen::Dynamic> ct::core::LDLTsolve ( const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &  A,
const Eigen::Matrix< SCALAR, Eigen::Dynamic, Eigen::Dynamic > &  B 
)

◆ transposeArray()

template<typename EIGEN_VECTOR_ARRAY_TYPE_IN , typename SCALAR = double>
DiscreteArray<Eigen::Matrix<SCALAR, -1, -1> > ct::core::transposeArray ( const EIGEN_VECTOR_ARRAY_TYPE_IN &  array)

this method transposes/flips an array of vectors into another array containing the scalar trajectories corresponding to each dimension of the input array.

Example: if a StateVectorArray<3> with a total length of 100 is the input, the output is a vector of lengt 3, which contains Eigen-Vectors of length 100 corresponding to the scalar sequence in each dimension of the input array.

Template Parameters
EIGEN_VECTOR_ARRAY_TYPE_INtype of the input array
SCALARprimitive type
Parameters
arraythe input array to be transposed
Returns
DiscreteArray<Eigen::Matrix<SCALAR, -1, -1>> the output (transposed) array.
Warning
this method is inefficient, to not call at in performance-critical code.

References i.