Templated partial implementation of StateSim. More...
#include <state_sim_template.hpp>
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... | |
StateSimTemplate & | operator= (const StateSimTemplate &_o) |
StateSimTemplate & | operator= (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... | |
State & | state0 () override |
Reference to the initial state. More... | |
State & | stateCf () override |
Reference to the actual closed-form state. More... | |
State & | stateNm () 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... | |
StateSim & | operator= (const StateSim &)=default |
StateSim & | operator= (StateSim &&)=delete |
virtual ParamFuncs * | paramFuncs ()=0 |
Returns (if applicable) reference of the parametric functions structure. Otherwise returns nullptr. More... | |
virtual ParamFuncsDist * | paramFuncsDist ()=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... | |
State & | operator= (const State &)=default |
State & | operator= (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 StateSPtr & | state (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 | |
State * | parent_ |
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 State & | minus (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 State & | plus (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... | |
Templated partial implementation of StateSim.
StateSize | Size of the full state. |
StateNmSize | Size of the numerically-evaluated state. |
Definition at line 48 of file state_sim_template.hpp.
|
default |
|
virtualdefault |
|
inline |
Definition at line 68 of file state_sim_template.hpp.
|
delete |
|
inlineoverridevirtual |
Performs one simulation step to parametrized arc length _arc.
Implements tuw::StateSim.
Definition at line 195 of file state_sim_template.hpp.
|
inline |
Definition at line 201 of file state_sim_template.hpp.
|
inlineoverridevirtual |
Clone-to-base-class-ptr function.
Implements tuw::State.
Definition at line 94 of file state_sim_template.hpp.
|
inline |
Definition at line 77 of file state_sim_template.hpp.
|
delete |
|
inlineoverridevirtual |
Set discretization type used in the simulation.
Implements tuw::StateSim.
Definition at line 124 of file state_sim_template.hpp.
|
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.
|
inlineoverridevirtual |
Reference to the initial state.
Implements tuw::StateSim.
Definition at line 145 of file state_sim_template.hpp.
|
inlineoverridevirtual |
Reference to the actual closed-form state.
Implements tuw::StateSim.
Definition at line 157 of file state_sim_template.hpp.
|
inlineoverridevirtual |
Reference to the actual numerical-computed state.
Implements tuw::StateSim.
Definition at line 151 of file state_sim_template.hpp.
|
inline |
Definition at line 218 of file state_sim_template.hpp.
|
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.
|
inlineoverridevirtual |
Access state variable based on index _i.
Implements tuw::State.
Definition at line 169 of file state_sim_template.hpp.
|
inlineoverridevirtual |
Const access state variable based on index _i.
Implements tuw::State.
Definition at line 182 of file state_sim_template.hpp.
|
inlineoverridevirtual |
Size of the state variables.
Implements tuw::State.
Definition at line 163 of file state_sim_template.hpp.
double tuw::StateSimTemplate< StateSize, StateNmSize >::arcOld |
Definition at line 225 of file state_sim_template.hpp.
|
private |
Pointer to the active discretization-method function.
Definition at line 244 of file state_sim_template.hpp.
|
protected |
Definition at line 228 of file state_sim_template.hpp.
|
protected |
State array storing the initial value.
Definition at line 232 of file state_sim_template.hpp.
|
protected |
State array storing the closed-form-computed value.
Definition at line 241 of file state_sim_template.hpp.
|
protected |
State array storing the numerical-computed value.
Definition at line 235 of file state_sim_template.hpp.
|
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.