Public Member Functions | Public Attributes | Protected Attributes | Private Attributes | List of all members
tuw::StateSimTemplate< StateSize, StateNmSize > Class Template Reference

Templated partial implementation of StateSim. More...

#include <state_sim_template.hpp>

Inheritance diagram for tuw::StateSimTemplate< StateSize, StateNmSize >:
Inheritance graph
[legend]

Public Member Functions

void advance (double _arc) override
 Performs one simulation step to parametrized arc length _arc. More...
 
void advanceODEInt (double _arc)
 
virtual StateSPtr cloneState () const override
 Clone-to-base-class-ptr function. More...
 
StateSimTemplateoperator= (const StateSimTemplate &_o)
 
StateSimTemplateoperator= (StateSimTemplate &&)=delete
 
void setDiscrType (const RungeKutta::DiscretizationType &_discrType) override
 Set discretization type used in the simulation. More...
 
void setState (StateSPtr &_otherState) override
 Sets the state variables to the values of _otherState. It also sets the control structure evaluation point at most at the new arc parametrization (if applicable). More...
 
Statestate0 () override
 Reference to the initial state. More...
 
StatestateCf () override
 Reference to the actual closed-form state. More...
 
StatestateNm () override
 Reference to the actual numerical-computed state. More...
 
 StateSimTemplate ()=default
 
 StateSimTemplate (const StateSimTemplate &_o)
 
 StateSimTemplate (StateSimTemplate &&)=delete
 
void sys1 (const std::array< double, StateNmSize > &_x, std::array< double, StateNmSize > &_dxdt, const double _t)
 
void toState0 () override
 Resets entire state to state0. It also sets the control structure evaluation point at most at the new arc parametrization (if applicable). More...
 
double & value (const std::size_t &_i) override
 Access state variable based on index _i. More...
 
const double & value (const std::size_t &_i) const override
 Const access state variable based on index _i. More...
 
size_t valueSize () const override
 Size of the state variables. More...
 
virtual ~StateSimTemplate ()=default
 
- Public Member Functions inherited from tuw::StateSim
virtual void advanceSet0 (const double &_tEnd, const double &_dt)
 
virtual StateSimUPtr cloneStateSim () const =0
 Clone-to-base-class-ptr function. More...
 
StateSimoperator= (const StateSim &)=default
 
StateSimoperator= (StateSim &&)=delete
 
virtual ParamFuncsparamFuncs ()=0
 Returns (if applicable) reference of the parametric functions structure. Otherwise returns nullptr. More...
 
virtual ParamFuncsDistparamFuncsDist ()=0
 Returns (if applicable) reference of the parametric functions distance-extended structure. Otherwise returns nullptr. More...
 
virtual void setStateCf (const double &_arc, const ParamFuncs::EvalArcGuarantee &_evalArcGuarantee=ParamFuncs::EvalArcGuarantee::AFTER_LAST)=0
 Sets closed-form state at arc _arc. More...
 
virtual void setStateCfNmStep (const double &_arc, const ParamFuncs::EvalArcGuarantee &_evalArcGuarantee=ParamFuncs::EvalArcGuarantee::AFTER_LAST)
 
virtual double stateArc () const =0
 Value of the current arc parametrization of the state. More...
 
virtual double stateDist () const =0
 Value of the current traveled distance of the state. More...
 
 StateSim ()=default
 
 StateSim (const StateSim &)=default
 
 StateSim (StateSim &&)=delete
 
virtual ~StateSim ()=default
 
- Public Member Functions inherited from tuw::State
void fromEIGENVec (const Eigen::VectorXd &_vec)
 Copies all values from an Eigen vector. The valueSize of the State object has to be equal with the Eigen vector size. More...
 
void fromSTLVec (const std::vector< double > &_vec)
 Copies all values from an STL vector. The valueSize of the State object has to be equal with the STL vector size. More...
 
Stateoperator= (const State &)=default
 
Stateoperator= (State &&)=default
 
virtual void resize (const size_t &_i)
 Resizes the array. More...
 
 State (State *_parent)
 
 State ()
 
 State (const State &)=default
 
 State (State &&)=default
 
virtual StateSPtrstate (const std::size_t &_i)
 Access sub-state based on index _i. More...
 
virtual size_t stateSize () const
 Size of the sub-states. More...
 
void toEIGENVec (Eigen::VectorXd &_vec)
 Converts all the array values to an Eigen vector. More...
 
void toSTLVec (std::vector< double > &_vec)
 Converts all the array values to an STL vector. More...
 
virtual void updateSize ()
 Performs internal manipulation when any of the underlying arrays are being resized. More...
 
virtual ~State ()=default
 

Public Attributes

double arcOld
 

Protected Attributes

std::shared_ptr< boost::numeric::odeint::runge_kutta4< std::array< double, StateNmSize > > > rk
 
StateArray< StateSize > state0_
 State array storing the initial value. More...
 
StateArray< StateSize-StateNmSize > stateCf_
 State array storing the closed-form-computed value. More...
 
StateArray< StateNmSize > stateNm_
 State array storing the numerical-computed value. More...
 
StateArray< StateNmSize > stateNmDotCache_
 State array caching the evaluation of the last call of the value transition function. More...
 
- Protected Attributes inherited from tuw::State
Stateparent_
 Pointer to the parent State structure. More...
 

Private Attributes

RungeKutta::DiscretizationFuncPtr discrFunc_
 Pointer to the active discretization-method function. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from tuw::State
static std::vector< double > & minus (State &_lhs, State &_rhs, std::vector< double > &_ans)
 Performs substraction. Left and right operand are required to have the same valueSize. More...
 
static Eigen::VectorXd & minus (State &_lhs, State &_rhs, Eigen::VectorXd &_ans)
 Performs substraction. Left and right operand are required to have the same valueSize. More...
 
static Stateminus (State &_lhs, State &_rhs, State &_ans)
 Performs substraction. Answer variable, left operand and right operand are required to have the same valueSize. More...
 
static std::vector< double > & plus (State &_lhs, State &_rhs, std::vector< double > &_ans)
 Performs addition. Left and right operand are required to have the same valueSize. More...
 
static Eigen::VectorXd & plus (State &_lhs, State &_rhs, Eigen::VectorXd &_ans)
 Performs addition. Left and right operand are required to have the same valueSize. More...
 
static Stateplus (State &_lhs, State &_rhs, State &_ans)
 Performs addition. Answer variable, left operand and right operand are required to have the same valueSize. More...
 
- Protected Member Functions inherited from tuw::State
void callRootUpdateSize ()
 Calls (if present) the parent updateSize procedure. Otherwise performs root updateSize. More...
 

Detailed Description

template<std::size_t StateSize, std::size_t StateNmSize>
class tuw::StateSimTemplate< StateSize, StateNmSize >

Templated partial implementation of StateSim.

Template Parameters
StateSizeSize of the full state.
StateNmSizeSize of the numerically-evaluated state.

Definition at line 48 of file state_sim_template.hpp.

Constructor & Destructor Documentation

template<std::size_t StateSize, std::size_t StateNmSize>
tuw::StateSimTemplate< StateSize, StateNmSize >::StateSimTemplate ( )
default
template<std::size_t StateSize, std::size_t StateNmSize>
virtual tuw::StateSimTemplate< StateSize, StateNmSize >::~StateSimTemplate ( )
virtualdefault
template<std::size_t StateSize, std::size_t StateNmSize>
tuw::StateSimTemplate< StateSize, StateNmSize >::StateSimTemplate ( const StateSimTemplate< StateSize, StateNmSize > &  _o)
inline

Definition at line 68 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
tuw::StateSimTemplate< StateSize, StateNmSize >::StateSimTemplate ( StateSimTemplate< StateSize, StateNmSize > &&  )
delete

Member Function Documentation

template<std::size_t StateSize, std::size_t StateNmSize>
void tuw::StateSimTemplate< StateSize, StateNmSize >::advance ( double  _arc)
inlineoverridevirtual

Performs one simulation step to parametrized arc length _arc.

Implements tuw::StateSim.

Definition at line 195 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
void tuw::StateSimTemplate< StateSize, StateNmSize >::advanceODEInt ( double  _arc)
inline

Definition at line 201 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
virtual StateSPtr tuw::StateSimTemplate< StateSize, StateNmSize >::cloneState ( ) const
inlineoverridevirtual

Clone-to-base-class-ptr function.

Implements tuw::State.

Definition at line 94 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
StateSimTemplate& tuw::StateSimTemplate< StateSize, StateNmSize >::operator= ( const StateSimTemplate< StateSize, StateNmSize > &  _o)
inline

Definition at line 77 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
StateSimTemplate& tuw::StateSimTemplate< StateSize, StateNmSize >::operator= ( StateSimTemplate< StateSize, StateNmSize > &&  )
delete
template<std::size_t StateSize, std::size_t StateNmSize>
void tuw::StateSimTemplate< StateSize, StateNmSize >::setDiscrType ( const RungeKutta::DiscretizationType _discrType)
inlineoverridevirtual

Set discretization type used in the simulation.

Implements tuw::StateSim.

Definition at line 124 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
void tuw::StateSimTemplate< StateSize, StateNmSize >::setState ( StateSPtr _otherState)
inlineoverridevirtual

Sets the state variables to the values of _otherState. It also sets the control structure evaluation point at most at the new arc parametrization (if applicable).

Implements tuw::StateSim.

Definition at line 130 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
State& tuw::StateSimTemplate< StateSize, StateNmSize >::state0 ( )
inlineoverridevirtual

Reference to the initial state.

Implements tuw::StateSim.

Definition at line 145 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
State& tuw::StateSimTemplate< StateSize, StateNmSize >::stateCf ( )
inlineoverridevirtual

Reference to the actual closed-form state.

Implements tuw::StateSim.

Definition at line 157 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
State& tuw::StateSimTemplate< StateSize, StateNmSize >::stateNm ( )
inlineoverridevirtual

Reference to the actual numerical-computed state.

Implements tuw::StateSim.

Definition at line 151 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
void tuw::StateSimTemplate< StateSize, StateNmSize >::sys1 ( const std::array< double, StateNmSize > &  _x,
std::array< double, StateNmSize > &  _dxdt,
const double  _t 
)
inline

Definition at line 218 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
void tuw::StateSimTemplate< StateSize, StateNmSize >::toState0 ( )
inlineoverridevirtual

Resets entire state to state0. It also sets the control structure evaluation point at most at the new arc parametrization (if applicable).

Implements tuw::StateSim.

Definition at line 110 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
double& tuw::StateSimTemplate< StateSize, StateNmSize >::value ( const std::size_t &  _i)
inlineoverridevirtual

Access state variable based on index _i.

Implements tuw::State.

Definition at line 169 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
const double& tuw::StateSimTemplate< StateSize, StateNmSize >::value ( const std::size_t &  _i) const
inlineoverridevirtual

Const access state variable based on index _i.

Implements tuw::State.

Definition at line 182 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
size_t tuw::StateSimTemplate< StateSize, StateNmSize >::valueSize ( ) const
inlineoverridevirtual

Size of the state variables.

Implements tuw::State.

Definition at line 163 of file state_sim_template.hpp.

Member Data Documentation

template<std::size_t StateSize, std::size_t StateNmSize>
double tuw::StateSimTemplate< StateSize, StateNmSize >::arcOld

Definition at line 225 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
RungeKutta::DiscretizationFuncPtr tuw::StateSimTemplate< StateSize, StateNmSize >::discrFunc_
private

Pointer to the active discretization-method function.

Definition at line 244 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
std::shared_ptr<boost::numeric::odeint::runge_kutta4<std::array<double, StateNmSize> > > tuw::StateSimTemplate< StateSize, StateNmSize >::rk
protected

Definition at line 228 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
StateArray<StateSize> tuw::StateSimTemplate< StateSize, StateNmSize >::state0_
protected

State array storing the initial value.

Definition at line 232 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
StateArray<StateSize - StateNmSize> tuw::StateSimTemplate< StateSize, StateNmSize >::stateCf_
protected

State array storing the closed-form-computed value.

Definition at line 241 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
StateArray<StateNmSize> tuw::StateSimTemplate< StateSize, StateNmSize >::stateNm_
protected

State array storing the numerical-computed value.

Definition at line 235 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
StateArray<StateNmSize> tuw::StateSimTemplate< StateSize, StateNmSize >::stateNmDotCache_
protected

State array caching the evaluation of the last call of the value transition function.

Definition at line 238 of file state_sim_template.hpp.


The documentation for this class was generated from the following file:


tuw_control
Author(s): George Todoran
autogenerated on Mon Jun 10 2019 15:27:23