Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tuw Namespace Reference

Namespaces

 cost_functions
 
 DiffDrive
 
 Edge8
 
 RungeKutta
 

Classes

class  Bla
 
class  ContainerSubStateMapArray
 
class  ContainerSubStateMapArrayEmpty
 
class  ContainerSubStateMapVector
 
class  ContainerSubStateMapVectorEmpty
 
class  CostsEvaluator
 
class  CostsEvaluatorBase
 
class  CostsEvaluatorCached
 
class  DataBuffer
 
class  DataBufferArray
 
class  DataBufferVector
 
struct  euler_abc
 
class  EvaluatedLattice
 
class  explicit_generic_rk_impl
 
struct  FuncCacheData
 
struct  FuncCtrlPt
 Control point variable. More...
 
struct  heun_abc
 
class  Integrator
 Minimal class performing numerically stable integration (using the Kahan summation algorithm). More...
 
class  KalmanFilter
 Minimal cass implementing the Extended Kalman Filter algorithm. More...
 
class  KalmanFilterInterface
 Interface for simplified manipulation of specialized (Extended) Kalman Filter implementations. More...
 
class  KalmanFilterLinOrd1
 Partial implementation of KalmanFilterPredictInterface for 1st order multivariate (linear) integrator systems. The state variables are expected to be ordered in a 2 * XDim vector where the first XDim variables are the order 0 states and the 2nd XDim variables are their corresponding derivatives. More...
 
class  KalmanFilterPredictInterface
 Interface for simplified manipulation of specialized (Extended) Kalman Filter prediction part. More...
 
class  KalmanFilterUpdateInterface
 Interface for simplified manipulation of specialized (Extended) Kalman Filter updates. To be used with KalmanFilterPredictInterface. More...
 
struct  LatticePoint
 Structure containing an evaluation arc and a state pointer. More...
 
class  LatticeTypeBaseCRTP
 
class  LatticeTypeStateSimBeginEnd
 
class  LatticeTypeStateSimCtrlPtKnots
 
class  LatticeTypeStateSimCtrlPtKnotsP
 
class  LatticeTypeStateSimCtrlPtKnotsV
 
class  LatticeTypeStateSimEqDs
 
class  LatticeTypeStateSimEqDt
 
class  LeafAccessTreeBase
 
class  LeafAccessTreeBaseCRTP
 
class  LeafAccessTreeBaseCRTP< Derived, LeafType, std::tuple< SetTypes... >, ContSize >
 
class  LeafAccessTreeBaseVirt
 
class  ModelStamps
 
class  OdeStateSolverDummyAlias
 
class  OdeStateSolverRealAlias
 
class  OptimizationState
 
class  ParamFuncs
 Storage and manipulation of parametric functions collection. More...
 
class  ParamFuncs2State
 Interface for a filter that outputs a desired state given an observed state and a parametric functions structure. More...
 
class  ParamFuncs2StateBase
 
class  ParamFuncsBase
 
struct  ParamFuncsBaseArcVarsDyn
 
struct  ParamFuncsBaseArcVarsStatic
 
class  ParamFuncsBaseCRTP
 
struct  ParamFuncsBaseFuncVarsDyn
 
struct  ParamFuncsBaseFuncVarsStatic
 
class  ParamFuncsBaseVirt
 
class  ParamFuncsDist
 Extends manipulation of parametric functions collection with closed-form arc length (distance) computation. More...
 
class  ParamFuncsDistBase
 
class  ParamFuncsDistBaseCRTP
 
class  ParamFuncsDistBaseVirt
 
class  ParamFuncsEvaluator
 Class manipulating a set of parametric-functions-to-state objects based on requested parametric functions input type. More...
 
class  ParamFuncsSpline0Dist
 
struct  ParamFuncsSpline0DistArcVarsDyn
 
struct  ParamFuncsSpline0DistArcVarsStatic
 
struct  ParamFuncsSpline0DistFuncVarsDyn
 
struct  ParamFuncsSpline0DistFuncVarsStatic
 
struct  ParamFuncsStructure
 Containts parametric function initialization data. More...
 
struct  RatioEval
 
struct  rk4_38_abc
 
class  State
 Generic tree-like recursive structure that allows sub-structure access as well as ordered (array-like) value access. More...
 
class  StateArray
 Implementation of State for a fixed size array of double values. More...
 
class  StateArrayScoped
 Extension of StateArray providing value access based on a scoped enumeration (compile-time). More...
 
class  StateFeedback
 Interface for a filter that outputs a desired state given an observed state and a desired state. More...
 
class  StateFeedback1Output
 Partial implementation of the StateFeedback interface for 1-dimensional output linear state-feedback filter types. More...
 
class  StateGradMapBase
 
class  StateGradWithMatMap
 
class  StateMapArray
 
class  StateMapBase
 
class  StateMapBaseCRTP
 
class  StateMapBaseVirt
 
class  StateMapping
 Interface for a filter that performs a (nonlinear) mapping from the input state to an output state. More...
 
class  StateMapTuple
 
class  StateMapVector
 
class  StateNestedArray
 Implementation of State being formed by an array of substates. More...
 
class  StateNestedArrayScoped
 Extension of StateNestedArray providing sub-state access based on a scoped enumeration (compile-time). More...
 
class  StateNestedSet
 Implementation of State being formed by tuple of substates. More...
 
class  StateNestedSetScoped
 Extension of StateNestedSet providing sub-state access based on a scoped enumeration (compile-time). More...
 
class  StateNestedVector
 
class  StateSim
 Interface for a state simulator structure that performs numerical integration of not-closed-form state variables. More...
 
class  StateSimBase
 
class  StateSimBaseCRTP
 
class  StateSimBaseVirt
 
class  StateSimTemplate
 Templated partial implementation of StateSim. More...
 
class  StateVector
 Implementation of State for a dynamic size vector of double values. More...
 
class  StateWithGradMapBase
 
class  StateWithGradMapSimBase
 
class  StateWithGradMapSimBaseInternal
 
struct  SubArrContainer
 
struct  SubEmpty
 
struct  SubSetContainer
 
struct  SubVecContainer
 dumb test More...
 
struct  TrajectoryOptimizer
 
class  TrajectorySimGrade
 
class  TrajectorySimulator
 
class  TrajectorySimulatorOnline
 
class  TrajectorySimulatorPrecalc
 
struct  ValArr
 
struct  ValRef
 
struct  ValVec
 

Typedefs

template<size_t HistSize, class TRKType >
using explicit_adams_bashforth = odeint::adams_bashforth< HistSize, typename TRKType::state_type, typename TRKType::value_type, typename TRKType::deriv_type, typename TRKType::time_type, typename TRKType::algebra_type, typename TRKType::operations_type, typename TRKType::resizer_type, TRKType >
 
using FuncEvalModesFlags = std::array< bool, nrModesMax_ >
 
using ModelStampsConstPtr = std::shared_ptr< ModelStamps const >
 
using ModelStampsPtr = std::shared_ptr< ModelStamps >
 
using OptimizationStateConstSPtr = std::shared_ptr< OptimizationState const >
 
using OptimizationStateConstUPtr = std::unique_ptr< OptimizationState const >
 
using OptimizationStateSPtr = std::shared_ptr< OptimizationState >
 
using OptimizationStateUPtr = std::unique_ptr< OptimizationState >
 
using ParamFuncsConstSPtr = std::shared_ptr< ParamFuncs const >
 
using ParamFuncsConstUPtr = std::unique_ptr< ParamFuncs const >
 
using ParamFuncsDistConstPtr = std::shared_ptr< ParamFuncsDist const >
 
using ParamFuncsDistPtr = std::shared_ptr< ParamFuncsDist >
 
using ParamFuncsSpline0DistConstPtr = std::shared_ptr< ParamFuncsSpline0Dist const >
 
using ParamFuncsSpline0DistPtr = std::shared_ptr< ParamFuncsSpline0Dist >
 
using ParamFuncsSPtr = std::shared_ptr< ParamFuncs >
 
using ParamFuncsUPtr = std::unique_ptr< ParamFuncs >
 
template<std::size_t N>
using StateArrayConstSPtr = std::shared_ptr< StateArray< N > const >
 
template<std::size_t N>
using StateArrayConstUPtr = std::unique_ptr< StateArray< N > const >
 
template<std::size_t N>
using StateArraySPtr = std::shared_ptr< StateArray< N >>
 
template<std::size_t N>
using StateArrayUPtr = std::unique_ptr< StateArray< N >>
 
using StateConstSPtr = std::shared_ptr< State const >
 
using StateConstUPtr = std::unique_ptr< State const >
 
template<class TNum , template< class, class > class TStateNm, template< class, class > class TStateCf>
using StateMap = StateMapBase< TNum, TStateNm< TNum, TNum >, TStateCf< TNum, TNum >>
 
template<class TLeafType , size_t TN>
using StateMapArrayD = StateMapArray< double, TLeafType, TN >
 
template<class TLeafType , size_t TN>
using StateMapArrayF = StateMapArray< float, TLeafType, TN >
 
template<class TLeafType , size_t TN>
using StateMapArrayI = StateMapArray< int, TLeafType, TN >
 
using StateMapBaseVirtD = StateMapBaseVirt< double >
 
using StateMapBaseVirtF = StateMapBaseVirt< float >
 
using StateMapBaseVirtI = StateMapBaseVirt< int >
 
template<typename... TLeafTypes>
using StateMapTupleD = StateMapArray< double, TLeafTypes... >
 
template<typename... TLeafTypes>
using StateMapTupleF = StateMapArray< float, TLeafTypes... >
 
template<typename... TLeafTypes>
using StateMapTupleI = StateMapArray< int, TLeafTypes... >
 
template<class TLeafType >
using StateMapVectorD = StateMapVector< double, TLeafType >
 
template<class TLeafType >
using StateMapVectorF = StateMapVector< float, TLeafType >
 
template<class TLeafType >
using StateMapVectorI = StateMapVector< int, TLeafType >
 
template<typename SubState , size_t N>
using StateNestedArrayConstSPtr = std::shared_ptr< StateNestedArray< SubState, N > const >
 
template<typename SubState , size_t N>
using StateNestedArrayConstUPtr = std::unique_ptr< StateNestedArray< SubState, N > const >
 
template<typename SubState , size_t N>
using StateNestedArraySPtr = std::shared_ptr< StateNestedArray< SubState, N >>
 
template<typename SubState , size_t N>
using StateNestedArrayUPtr = std::unique_ptr< StateNestedArray< SubState, N >>
 
template<typename... NestedStates>
using StateNestedSetConstSPtr = std::shared_ptr< StateNestedSet< NestedStates... > const >
 
template<typename... NestedStates>
using StateNestedSetConstUPtr = std::unique_ptr< StateNestedSet< NestedStates... > const >
 
template<typename... NestedStates>
using StateNestedSetSPtr = std::shared_ptr< StateNestedSet< NestedStates... > >
 
template<typename... NestedStates>
using StateNestedSetUPtr = std::unique_ptr< StateNestedSet< NestedStates... > >
 
template<typename SubState >
using StateNestedVectorConstSPtr = std::shared_ptr< StateNestedVector< SubState > const >
 
template<typename SubState >
using StateNestedVectorConstUPtr = std::unique_ptr< StateNestedVector< SubState > const >
 
template<typename SubState >
using StateNestedVectorSPtr = std::shared_ptr< StateNestedVector< SubState > >
 
template<typename SubState >
using StateNestedVectorUPtr = std::unique_ptr< StateNestedVector< SubState > >
 
template<class TNumType >
using StateSimBaseVirtMap = StateSimBaseVirt< TNumType, StateMapBaseVirt< TNumType >>
 
using StateSimConstSPtr = std::shared_ptr< StateSim const >
 
using StateSimConstUPtr = std::unique_ptr< StateSim const >
 
using StateSimPtr = std::shared_ptr< StateSim >
 
using StateSimSPtr = std::shared_ptr< StateSim >
 
template<std::size_t StateSize, std::size_t StateNmSize>
using StateSimTemplateConstSPtr = std::shared_ptr< StateSimTemplate< StateSize, StateNmSize > const >
 
template<std::size_t StateSize, std::size_t StateNmSize>
using StateSimTemplateConstUPtr = std::unique_ptr< StateSimTemplate< StateSize, StateNmSize > const >
 
template<std::size_t StateSize, std::size_t StateNmSize>
using StateSimTemplateSPtr = std::shared_ptr< StateSimTemplate< StateSize, StateNmSize >>
 
template<std::size_t StateSize, std::size_t StateNmSize>
using StateSimTemplateUPtr = std::unique_ptr< StateSimTemplate< StateSize, StateNmSize >>
 
using StateSimUPtr = std::unique_ptr< StateSim >
 
using StateSPtr = std::shared_ptr< State >
 
using StateUPtr = std::unique_ptr< State >
 
using StateVectorConstSPtr = std::shared_ptr< StateVector const >
 
using StateVectorConstUPtr = std::unique_ptr< StateVector const >
 
using StateVectorSPtr = std::shared_ptr< StateVector >
 
using StateVectorUPtr = std::unique_ptr< StateVector >
 
template<class TNum , template< class, class > class TStateNm, template< class, class > class TStateCf, template< class, class > class TOptVarStruct>
using StateWithGradMap = StateWithGradMapBase< TNum, TStateNm, TStateCf, TOptVarStruct >
 
using TrajectoryOptimizerConstSPtr = std::shared_ptr< TrajectoryOptimizer const >
 
using TrajectoryOptimizerConstUPtr = std::unique_ptr< TrajectoryOptimizer const >
 
using TrajectoryOptimizerSPtr = std::shared_ptr< TrajectoryOptimizer >
 
using TrajectoryOptimizerUPtr = std::unique_ptr< TrajectoryOptimizer >
 
using TrajectorySimGradeConstSPtr = std::shared_ptr< TrajectorySimGrade const >
 
using TrajectorySimGradeConstUPtr = std::unique_ptr< TrajectorySimGrade const >
 
using TrajectorySimGradeSPtr = std::shared_ptr< TrajectorySimGrade >
 
using TrajectorySimGradeUPtr = std::unique_ptr< TrajectorySimGrade >
 
using TrajectorySimulatorConstSPtr = std::shared_ptr< TrajectorySimulator const >
 
using TrajectorySimulatorConstUPtr = std::unique_ptr< TrajectorySimulator const >
 
using TrajectorySimulatorSPtr = std::shared_ptr< TrajectorySimulator >
 
using TrajectorySimulatorUPtr = std::unique_ptr< TrajectorySimulator >
 

Enumerations

enum  CostEvaluatorCostType { CostEvaluatorCostType::F, CostEvaluatorCostType::H, CostEvaluatorCostType::G, CostEvaluatorCostType::ENUM_SIZE }
 
enum  CtrlPtDim { CtrlPtDim::VAL, CtrlPtDim::ARC }
 Control point variable dimension. More...
 
enum  EvalArcGuarantee { EvalArcGuarantee::NONE, EvalArcGuarantee::NEAR_LAST, EvalArcGuarantee::AT_BEGIN, EvalArcGuarantee::AT_END }
 Flags if any guarantees about evaluation arc relative to last evaluation arc are present. More...
 
enum  FuncEvalMode {
  FuncEvalMode::DIFF1, FuncEvalMode::DIFF2, FuncEvalMode::INT1, FuncEvalMode::INT2,
  FuncEvalMode::FUNC, FuncEvalMode::ENUM_SIZE
}
 Required type of computation relative to the parametric function. More...
 
enum  OptCacheType { OptCacheType::LAST1, OptCacheType::LAST2, OptCacheType::ITER_START, OptCacheType::ENUM_SIZE }
 
enum  TraveledDistCfMode { TraveledDistCfMode::NONE, TraveledDistCfMode::V, TraveledDistCfMode::AV }
 Required type of traveled distance computation relative to the parametric function. More...
 

Functions

template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void advanceFuncSimGrad (const TNumType &_arcNow)
 
template<typename Enumeration >
constexpr auto asInt (Enumeration const value) -> typename std::underlying_type< Enumeration >::type
 
template<bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
void bindAdvanceFunc ()
 
template<bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
void bindAdvanceFuncGrad ()
 
size_t bindFromPartLatticesToSimLattice (const bool &_saveLatticeStates=false)
 
template<typename TSimType2 , typename TLatticePointType >
static void copyDataFromSimToSimLatticeI (const TSimType2 &_sim, TLatticePointType &_latticePtI)
 
template<typename TSimType2 , typename TLatticePointType , bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
static void copyDataNmFromSimToSimLatticeI (const TSimType2 &_sim, TLatticePointType &_latticePtI)
 
template<typename TSimType2 , typename TLatticePointType , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void copyGradDataFromSimToSimLatticeI (const TSimType2 &_sim, TLatticePointType &_latticePtI)
 
template<typename TSimType2 , typename TLatticePointType , bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
static void copyGradDataNmFromSimToSimLatticeI (const TSimType2 &_sim, TLatticePointType &_latticePtI)
 
template<typename TSimType2 , typename TLatticePointType , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
void copyReqDataFromSimToSimLatticeI (const TSimType2 &_sim, TLatticePointType &_latticePtI)
 
template<typename TSimType2 , typename TLatticePointType , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void copyStructureFromSimToSimLatticeI (const TSimType2 &_sim, TLatticePointType &_latticePtI)
 
template<std::size_t IIMax, std::size_t II = 0>
constexpr std::enable_if<(II==IIMax), void >::type eval_all_costs (TNumType *&_cfPtr, TNumType *&_cfGradPtr, const size_t &_optParamSize)
 
template<std::size_t IIMax, std::size_t II = 0>
constexpr std::enable_if<(II< IIMax), void >::type eval_all_costs (TNumType *&_cfPtr, TNumType *&_cfGradPtr, const size_t &_optParamSize)
 
template<size_t FuncNr = 0>
void evaluateCosts (TNumType *&_cfPtr, TNumType *&_cfGradPtr, const size_t &_optParamSize)
 
template<std::size_t II = 0, class FuncT , typename... Tp>
constexpr std::enable_if< II==sizeof...(Tp), void >::type for_each_tuple (std::tuple< Tp... > &, FuncT)
 
template<std::size_t II = 0, class FuncT , typename... Tp>
constexpr std::enable_if< II==sizeof...(Tp), void >::type for_each_tuple_class (std::tuple< Tp... > &, FuncT &)
 
void getMinArcLatCacheIdx (typename std::vector< LatticePointType >::iterator *&_itMin, size_t &_latVecIdx)
 
template<class TNumType >
static bool isSame (const Eigen::Matrix< TNumType,-1, 1 > &_optVar0, const Eigen::Matrix< TNumType,-1, 1 > &_optVar1)
 
template<typename T >
normalizeRad (T _x)
 
size_t populatePartLattices (size_t &_sizeCosts)
 
void resizeCosts (const size_t &_optParamSize, const bool &_simulatingWithGrad)
 
void resizeInternal ()
 
void resizeSimLattice (const size_t &_totalPartLatticePtsSize)
 
template<bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
void setXNmDot (const TNumType &_arcNow)
 
template<typename T >
constexpr int signum (T x, std::false_type is_signed)
 
template<typename T >
constexpr int signum (T x, std::true_type is_signed)
 
template<typename T >
constexpr int signum (T x)
 
void simulateTrajectory (const bool &_saveLatticeStates=false)
 
void simulateTrajectoryImpl (const bool &_saveLatticeStates=false)
 
template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void simulateTrajectoryWithGrad (const bool &_saveLatticeStates=false)
 
 TEST (TestStateMap, CopyAssignmentOperatorArray)
 
 TEST (TestStateMap, CopyAssignmentOperatorVector)
 
 TEST (TestStateMap, CopyAssignmentOperatorTuple)
 
 TEST (TestStateMap, ExtendedClassInStateMap)
 
 TEST (TestStateMap, NestedArrayVectorOneLvl)
 
 TEST (TestStateMap, NestedArraysCompileTimeSize)
 
 TEST (TestStateMap, NestedVectorsCompileTimeSize)
 
 TEST (TestStateMap, NestedArraysVectorsCompileTimeSize)
 
 TEST (TestStateMap, NestedTupleCompileTimeSize)
 
 TEST (TestStateMap, NestedStateResize)
 
 TEST (TestStateMap, ResizeWithEmptyVectors)
 
 TEST (TestStateMap, NestedArraysDataBuffer)
 
 TEST (TestStateMap, VirtualBase)
 

Variables

template<std::size_t II = 0, class FuncT , typename... Tp>
constexpr std::enable_if< II< sizeof...(Tp), void >::type for_each_tuple_class(std::tuple< Tp... > &t, FuncT &f){f[II]=[&t](const auto &_a, const auto &_b, const auto &_c, auto &_d){std::get< II >t).computeDArcIdPImpl(_a, _b, _c, _d);};for_each_tuple_class< II+1, FuncT, Tp... >t, f);}template< std::size_t IIMax, std::size_t II=0 >constexpr inline typename std::enable_if<(II==IIMax), void >::type get_costs_sizes(auto &partLatI, const size_t &_i, auto &_sizeCostsPerPartLattice, auto &_sizeCostsPerType){}template< std::size_t IIMax, std::size_t II=0 >constexpr inline typename std::enable_if<(II< IIMax), void >::type get_costs_sizes(auto &partLatI, const size_t &_i, auto &_sizeCostsPerPartLattice, auto &_sizeCostsPerType){size_t partLatICostsTypeJ=partLatI.lattice.size()*partLatI.template costFuncsNr< II >);_sizeCostsPerPartLattice[_i]+=partLatICostsTypeJ;_sizeCostsPerType[II]+=partLatICostsTypeJ;get_costs_sizes< IIMax, II+1 >partLatI, _i, _sizeCostsPerPartLattice, _sizeCostsPerType);}template< typename TNumType, typename TSimType, bool TUseStateNm, template< typename, typename > class...TLatticeTypes >class TrajectorySimulator{public:using StateSimSPtr=std::shared_ptr< TSimType >;public:using StateType=typename TSimType::StateType;public:using StateSPtr=std::shared_ptr< StateType >;public:using StateForSimType=typename TSimType::StateForSimType;public:using LatticePointType=LatticePoint< TNumType, StateType >;public:static constexpr const bool CanComputeStateGrad=!std::is_same< EmptyGradType, typename StateMapBaseTraits< StateType >::StateWithGradNmType >::value;public:static constexpr const size_t CostFuncsTypesNr=std::tuple_element< 0, std::tuple< TLatticeTypes< TNumType, TSimType >... > >::type::costFuncsTypesNr();public:TrajectorySimulator():stateSim_(std::shared_ptr< TSimType >new TSimType)){for_each_tuple_class(partialLattices_, correctStateGradFunc);for(size_t i=0;i< gradCostsMap_.size();++i){gradCostsMap_[i]=std::shared_ptr< Eigen::Map< Eigen::Matrix< TNumType,-1,-1, Eigen::RowMajor > > >new Eigen::Map< Eigen::Matrix< TNumType,-1,-1, Eigen::RowMajor > >nullptr, 0, 0));}}public:TrajectorySimulator(StateSimSPtr &_stateSim):stateSim_(_stateSim){for_each_tuple_class(partialLattices_, correctStateGradFunc);for(size_t i=0;i< gradCostsMap_.size();++i){gradCostsMap_[i]=std::shared_ptr< Eigen::Map< Eigen::Matrix< TNumType,-1,-1, Eigen::RowMajor > > >new Eigen::Map< Eigen::Matrix< TNumType,-1,-1, Eigen::RowMajor > >nullptr, 0, 0));}}public:StateSimSPtr &stateSim(){return stateSim_;}public:const StateSimSPtr &stateSim() const {return stateSim_;}public:LatticePointType &simLatticeI(const size_t &_i){return simulationLattice_[_i];}public:const LatticePointType &simLatticeI(const size_t &_i) const {return simulationLattice_[_i];}public:size_t simLatticeSize() const {return simulationLatticeActiveSize_;}public:template< template< typename, typename > class TLatticeType > TLatticeType< TNumType, TSimType > &partialLattice(){return std::get< TLatticeType< TNumType, TSimType > >partialLattices_);}public:template< template< typename, typename > class TLatticeType > const TLatticeType< TNumType, TSimType > &partialLattice() const {return std::get< TLatticeType< TNumType, TSimType > >partialLattices_);}public:template< size_t TLatticeIdx > auto &partialLattice(){return std::get< TLatticeIdx >partialLattices_);}public:template< size_t TLatticeIdx > const auto &partialLattice() const {return std::get< TLatticeIdx >partialLattices_);}private:using AdvanceFunction=void(TrajectorySimulator< TNumType, TSimType, TUseStateNm, TLatticeTypes... >::*)(const TNumType &);private:AdvanceFunction advanceFunc;private:void advanceFuncSimEmpty(const TNumType &_arcNow){}private:void advanceFuncSim(const TNumType &_arcNow){stateSim_-> advance (_arcNow)
 
std::array< std::function< void(const TSimType &, const TNumType &, const size_t &, typename StateMapBaseTraits< typename StateType::StateMapBaseType >::StateGradType &)>, sizeof...(TLatticeTypes)> correctStateGradFunc
 
StateMapArray< TNumType, StateMapVector< TNumType, TNumType >, CostFuncsTypesNr > costs_
 
StateMapArray< TNumType, StateMapVector< TNumType, StateMapVector< TNumType, TNumType > >, CostFuncsTypesNr > gradCosts_
 
std::array< std::shared_ptr< Eigen::Map< Eigen::Matrix< TNumType,-1,-1, Eigen::RowMajor > > >, CostFuncsTypesNr > gradCostsMap_
 
static constexpr const std::size_t nrModesMax_ = asInt(FuncEvalMode::ENUM_SIZE) - 1
 Maximum number of computation modes (except the parametric function itself FUNC). Currently 4 other choices supported. More...
 
std::tuple< TLatticeTypes< TNumType, TSimType >... > partialLattices_
 Vector containing the ordered sequence of arc parametrizations for each of the used lattices. More...
 
bool simulatingWithGrad
 
std::vector< LatticePointType > simulationLattice_
 Lattice requesting each simulated trajectory state. More...
 
size_t simulationLatticeActiveSize_
 
std::array< size_t, sizeof...(TLatticeTypes)> sizeCosts_
 
std::array< size_t, sizeof...(TLatticeTypes)> sizeCostsPerPartLattice_
 
std::array< size_t, CostFuncsTypesNr > sizeCostsPerType_
 
StateSimSPtr stateSim_
 State simulator object. More...
 

Typedef Documentation

template<size_t HistSize, class TRKType >
using tuw::explicit_adams_bashforth = typedef odeint::adams_bashforth<HistSize, typename TRKType::state_type, typename TRKType::value_type, typename TRKType::deriv_type, typename TRKType::time_type, typename TRKType::algebra_type, typename TRKType::operations_type, typename TRKType::resizer_type, TRKType>

Definition at line 146 of file discretization_options.hpp.

using tuw::FuncEvalModesFlags = typedef std::array<bool, nrModesMax_>

Definition at line 72 of file param_func.hpp.

using tuw::ModelStampsConstPtr = typedef std::shared_ptr<ModelStamps const>

Definition at line 42 of file model_stamps.h.

using tuw::ModelStampsPtr = typedef std::shared_ptr<ModelStamps>

Definition at line 41 of file model_stamps.h.

using tuw::OptimizationStateConstSPtr = typedef std::shared_ptr<OptimizationState const>

Definition at line 45 of file trajectory_optimizer.h.

using tuw::OptimizationStateConstUPtr = typedef std::unique_ptr<OptimizationState const>

Definition at line 47 of file trajectory_optimizer.h.

using tuw::OptimizationStateSPtr = typedef std::shared_ptr<OptimizationState>

Definition at line 44 of file trajectory_optimizer.h.

using tuw::OptimizationStateUPtr = typedef std::unique_ptr<OptimizationState>

Definition at line 46 of file trajectory_optimizer.h.

using tuw::ParamFuncsConstSPtr = typedef std::shared_ptr<ParamFuncs const>

Definition at line 56 of file param_func.h.

using tuw::ParamFuncsConstUPtr = typedef std::unique_ptr<ParamFuncs const>

Definition at line 54 of file param_func.h.

typedef std::shared_ptr< ParamFuncsDist const > tuw::ParamFuncsDistConstPtr

Definition at line 50 of file param_func_dist.h.

typedef std::shared_ptr< ParamFuncsDist > tuw::ParamFuncsDistPtr

Definition at line 49 of file param_func_dist.h.

using tuw::ParamFuncsSpline0DistConstPtr = typedef std::shared_ptr<ParamFuncsSpline0Dist const>

Definition at line 52 of file param_func_spline0_dist.h.

using tuw::ParamFuncsSpline0DistPtr = typedef std::shared_ptr<ParamFuncsSpline0Dist>

Definition at line 51 of file param_func_spline0_dist.h.

using tuw::ParamFuncsSPtr = typedef std::shared_ptr<ParamFuncs>

Definition at line 55 of file param_func.h.

using tuw::ParamFuncsUPtr = typedef std::unique_ptr<ParamFuncs>

Definition at line 53 of file param_func.h.

template<std::size_t N>
using tuw::StateArrayConstSPtr = typedef std::shared_ptr<StateArray<N> const>

Definition at line 54 of file state_array.hpp.

template<std::size_t N>
using tuw::StateArrayConstUPtr = typedef std::unique_ptr<StateArray<N> const>

Definition at line 58 of file state_array.hpp.

template<std::size_t N>
using tuw::StateArraySPtr = typedef std::shared_ptr<StateArray<N>>

Definition at line 52 of file state_array.hpp.

template<std::size_t N>
using tuw::StateArrayUPtr = typedef std::unique_ptr<StateArray<N>>

Definition at line 56 of file state_array.hpp.

using tuw::StateConstSPtr = typedef std::shared_ptr<State const>

Definition at line 130 of file state.h.

using tuw::StateConstUPtr = typedef std::unique_ptr<State const>

Definition at line 132 of file state.h.

template<class TNum , template< class, class > class TStateNm, template< class, class > class TStateCf>
using tuw::StateMap = typedef StateMapBase<TNum, TStateNm<TNum, TNum>, TStateCf<TNum, TNum>>

Definition at line 91 of file state_sim.hpp.

template<class TLeafType , size_t TN>
using tuw::StateMapArrayD = typedef StateMapArray<double, TLeafType, TN>

Definition at line 55 of file state_map.hpp.

template<class TLeafType , size_t TN>
using tuw::StateMapArrayF = typedef StateMapArray<float, TLeafType, TN>

Definition at line 57 of file state_map.hpp.

template<class TLeafType , size_t TN>
using tuw::StateMapArrayI = typedef StateMapArray<int, TLeafType, TN>

Definition at line 59 of file state_map.hpp.

using tuw::StateMapBaseVirtD = typedef StateMapBaseVirt<double>

Definition at line 43 of file state_map.hpp.

using tuw::StateMapBaseVirtF = typedef StateMapBaseVirt<float>

Definition at line 44 of file state_map.hpp.

Definition at line 45 of file state_map.hpp.

template<typename... TLeafTypes>
using tuw::StateMapTupleD = typedef StateMapArray<double, TLeafTypes...>

Definition at line 62 of file state_map.hpp.

template<typename... TLeafTypes>
using tuw::StateMapTupleF = typedef StateMapArray<float, TLeafTypes...>

Definition at line 64 of file state_map.hpp.

template<typename... TLeafTypes>
using tuw::StateMapTupleI = typedef StateMapArray<int, TLeafTypes...>

Definition at line 66 of file state_map.hpp.

template<class TLeafType >
using tuw::StateMapVectorD = typedef StateMapVector<double, TLeafType>

Definition at line 48 of file state_map.hpp.

template<class TLeafType >
using tuw::StateMapVectorF = typedef StateMapVector<float, TLeafType>

Definition at line 50 of file state_map.hpp.

template<class TLeafType >
using tuw::StateMapVectorI = typedef StateMapVector<int, TLeafType>

Definition at line 52 of file state_map.hpp.

template<typename SubState , size_t N>
using tuw::StateNestedArrayConstSPtr = typedef std::shared_ptr<StateNestedArray<SubState, N> const>

Definition at line 54 of file state_nested_array.h.

template<typename SubState , size_t N>
using tuw::StateNestedArrayConstUPtr = typedef std::unique_ptr<StateNestedArray<SubState, N> const>

Definition at line 58 of file state_nested_array.h.

template<typename SubState , size_t N>
using tuw::StateNestedArraySPtr = typedef std::shared_ptr<StateNestedArray<SubState, N>>

Definition at line 52 of file state_nested_array.h.

template<typename SubState , size_t N>
using tuw::StateNestedArrayUPtr = typedef std::unique_ptr<StateNestedArray<SubState, N>>

Definition at line 56 of file state_nested_array.h.

template<typename... NestedStates>
using tuw::StateNestedSetConstSPtr = typedef std::shared_ptr<StateNestedSet<NestedStates...> const>

Definition at line 53 of file state_nested_set.h.

template<typename... NestedStates>
using tuw::StateNestedSetConstUPtr = typedef std::unique_ptr<StateNestedSet<NestedStates...> const>

Definition at line 57 of file state_nested_set.h.

template<typename... NestedStates>
using tuw::StateNestedSetSPtr = typedef std::shared_ptr<StateNestedSet<NestedStates...> >

Definition at line 51 of file state_nested_set.h.

template<typename... NestedStates>
using tuw::StateNestedSetUPtr = typedef std::unique_ptr<StateNestedSet<NestedStates...> >

Definition at line 55 of file state_nested_set.h.

template<typename SubState >
using tuw::StateNestedVectorConstSPtr = typedef std::shared_ptr<StateNestedVector<SubState> const>

Definition at line 53 of file state_nested_vector.h.

template<typename SubState >
using tuw::StateNestedVectorConstUPtr = typedef std::unique_ptr<StateNestedVector<SubState> const>

Definition at line 57 of file state_nested_vector.h.

template<typename SubState >
using tuw::StateNestedVectorSPtr = typedef std::shared_ptr<StateNestedVector<SubState> >

Definition at line 51 of file state_nested_vector.h.

template<typename SubState >
using tuw::StateNestedVectorUPtr = typedef std::unique_ptr<StateNestedVector<SubState> >

Definition at line 55 of file state_nested_vector.h.

template<class TNumType >
using tuw::StateSimBaseVirtMap = typedef StateSimBaseVirt<TNumType, StateMapBaseVirt<TNumType>>

Definition at line 658 of file state_sim.hpp.

using tuw::StateSimConstSPtr = typedef std::shared_ptr<StateSim const>

Definition at line 55 of file state_sim.h.

using tuw::StateSimConstUPtr = typedef std::unique_ptr<StateSim const>

Definition at line 57 of file state_sim.h.

using tuw::StateSimPtr = typedef std::shared_ptr<StateSim>

Definition at line 44 of file discretization_runge_kutta_alias.hpp.

using tuw::StateSimSPtr = typedef std::shared_ptr<StateSim>

Definition at line 54 of file state_sim.h.

template<std::size_t StateSize, std::size_t StateNmSize>
using tuw::StateSimTemplateConstSPtr = typedef std::shared_ptr<StateSimTemplate<StateSize, StateNmSize> const>

Definition at line 52 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
using tuw::StateSimTemplateConstUPtr = typedef std::unique_ptr<StateSimTemplate<StateSize, StateNmSize> const>

Definition at line 56 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
using tuw::StateSimTemplateSPtr = typedef std::shared_ptr<StateSimTemplate<StateSize, StateNmSize>>

Definition at line 50 of file state_sim_template.hpp.

template<std::size_t StateSize, std::size_t StateNmSize>
using tuw::StateSimTemplateUPtr = typedef std::unique_ptr<StateSimTemplate<StateSize, StateNmSize>>

Definition at line 54 of file state_sim_template.hpp.

using tuw::StateSimUPtr = typedef std::unique_ptr<StateSim>

Definition at line 56 of file state_sim.h.

using tuw::StateSPtr = typedef std::shared_ptr<State>

Definition at line 129 of file state.h.

using tuw::StateUPtr = typedef std::unique_ptr<State>

Definition at line 131 of file state.h.

using tuw::StateVectorConstSPtr = typedef std::shared_ptr<StateVector const>

Definition at line 50 of file state_vector.hpp.

using tuw::StateVectorConstUPtr = typedef std::unique_ptr<StateVector const>

Definition at line 52 of file state_vector.hpp.

using tuw::StateVectorSPtr = typedef std::shared_ptr<StateVector>

Definition at line 49 of file state_vector.hpp.

using tuw::StateVectorUPtr = typedef std::unique_ptr<StateVector>

Definition at line 51 of file state_vector.hpp.

template<class TNum , template< class, class > class TStateNm, template< class, class > class TStateCf, template< class, class > class TOptVarStruct>
using tuw::StateWithGradMap = typedef StateWithGradMapBase<TNum, TStateNm, TStateCf, TOptVarStruct>

Definition at line 606 of file state_sim.hpp.

using tuw::TrajectoryOptimizerConstSPtr = typedef std::shared_ptr<TrajectoryOptimizer const>

Definition at line 102 of file trajectory_optimizer.h.

using tuw::TrajectoryOptimizerConstUPtr = typedef std::unique_ptr<TrajectoryOptimizer const>

Definition at line 104 of file trajectory_optimizer.h.

using tuw::TrajectoryOptimizerSPtr = typedef std::shared_ptr<TrajectoryOptimizer>

Definition at line 101 of file trajectory_optimizer.h.

using tuw::TrajectoryOptimizerUPtr = typedef std::unique_ptr<TrajectoryOptimizer>

Definition at line 103 of file trajectory_optimizer.h.

using tuw::TrajectorySimGradeConstSPtr = typedef std::shared_ptr<TrajectorySimGrade const>

Definition at line 48 of file trajectory_sim_grade.h.

using tuw::TrajectorySimGradeConstUPtr = typedef std::unique_ptr<TrajectorySimGrade const>

Definition at line 50 of file trajectory_sim_grade.h.

using tuw::TrajectorySimGradeSPtr = typedef std::shared_ptr<TrajectorySimGrade>

Definition at line 47 of file trajectory_sim_grade.h.

using tuw::TrajectorySimGradeUPtr = typedef std::unique_ptr<TrajectorySimGrade>

Definition at line 49 of file trajectory_sim_grade.h.

using tuw::TrajectorySimulatorConstSPtr = typedef std::shared_ptr<TrajectorySimulator const>

Definition at line 47 of file trajectory_simulator.h.

using tuw::TrajectorySimulatorConstUPtr = typedef std::unique_ptr<TrajectorySimulator const>

Definition at line 49 of file trajectory_simulator.h.

using tuw::TrajectorySimulatorSPtr = typedef std::shared_ptr<TrajectorySimulator>

Definition at line 46 of file trajectory_simulator.h.

using tuw::TrajectorySimulatorUPtr = typedef std::unique_ptr<TrajectorySimulator>

Definition at line 48 of file trajectory_simulator.h.

Enumeration Type Documentation

Enumerator
ENUM_SIZE 

Definition at line 49 of file costs_evaluator.hpp.

enum tuw::CtrlPtDim
strong

Control point variable dimension.

Enumerator
VAL 

control point value

ARC 

control point arc parameter

Definition at line 55 of file param_func.hpp.

enum tuw::EvalArcGuarantee
strong

Flags if any guarantees about evaluation arc relative to last evaluation arc are present.

Enumerator
NONE 
NEAR_LAST 

close to previous evaluation arc

AT_BEGIN 

this evaluation arc is at the arc parametrization begin

AT_END 

this evaluation arc is at the arc parametrization end

Definition at line 61 of file param_func.hpp.

enum tuw::FuncEvalMode
strong

Required type of computation relative to the parametric function.

Enumerator
DIFF1 

function first derivative

DIFF2 

function second derivative

INT1 

function single integral

INT2 

function double integral

FUNC 

function value (always assumed to have the highest integer value of the enum)

ENUM_SIZE 

Definition at line 45 of file param_func.hpp.

enum tuw::OptCacheType
strong
Enumerator
LAST1 
LAST2 
ITER_START 
ENUM_SIZE 

Definition at line 86 of file trajectory_optimizer.hpp.

Required type of traveled distance computation relative to the parametric function.

Enumerator
NONE 

no closed-form distance computation mode

agent base center linear velocity is parametric function

AV 

agent base center linear acceleration is parametric function

Definition at line 54 of file param_func_dist.hpp.

Function Documentation

template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void tuw::advanceFuncSimGrad ( const TNumType &  _arcNow)
private

Definition at line 411 of file 2/trajectory_simulator.hpp.

template<typename Enumeration >
constexpr auto tuw::asInt ( Enumeration const  value) -> typename std::underlying_type<Enumeration>::type

Definition at line 87 of file utils.h.

template<bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
void tuw::bindAdvanceFunc ( )
private

Definition at line 421 of file 2/trajectory_simulator.hpp.

template<bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
void tuw::bindAdvanceFuncGrad ( )
private

Definition at line 435 of file 2/trajectory_simulator.hpp.

size_t tuw::bindFromPartLatticesToSimLattice ( const bool &  _saveLatticeStates = false)
private

Definition at line 623 of file 2/trajectory_simulator.hpp.

template<typename TSimType2 , typename TLatticePointType >
static void tuw::copyDataFromSimToSimLatticeI ( const TSimType2 &  _sim,
TLatticePointType &  _latticePtI 
)
staticprivate

Definition at line 768 of file 2/trajectory_simulator.hpp.

template<typename TSimType2 , typename TLatticePointType , bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
static void tuw::copyDataNmFromSimToSimLatticeI ( const TSimType2 &  _sim,
TLatticePointType &  _latticePtI 
)
staticprivate

Definition at line 735 of file 2/trajectory_simulator.hpp.

template<typename TSimType2 , typename TLatticePointType , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void tuw::copyGradDataFromSimToSimLatticeI ( const TSimType2 &  _sim,
TLatticePointType &  _latticePtI 
)
staticprivate

Definition at line 779 of file 2/trajectory_simulator.hpp.

template<typename TSimType2 , typename TLatticePointType , bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
static void tuw::copyGradDataNmFromSimToSimLatticeI ( const TSimType2 &  _sim,
TLatticePointType &  _latticePtI 
)
staticprivate

Definition at line 752 of file 2/trajectory_simulator.hpp.

template<typename TSimType2 , typename TLatticePointType , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
void tuw::copyReqDataFromSimToSimLatticeI ( const TSimType2 &  _sim,
TLatticePointType &  _latticePtI 
)
private

Definition at line 715 of file 2/trajectory_simulator.hpp.

template<typename TSimType2 , typename TLatticePointType , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void tuw::copyStructureFromSimToSimLatticeI ( const TSimType2 &  _sim,
TLatticePointType &  _latticePtI 
)
staticprivate

Definition at line 790 of file 2/trajectory_simulator.hpp.

template<std::size_t IIMax, std::size_t II = 0>
constexpr std::enable_if<(II == IIMax), void>::type tuw::eval_all_costs ( TNumType *&  _cfPtr,
TNumType *&  _cfGradPtr,
const size_t &  _optParamSize 
)

Definition at line 466 of file 2/trajectory_simulator.hpp.

template<std::size_t IIMax, std::size_t II = 0>
constexpr std::enable_if<(II < IIMax), void>::type tuw::eval_all_costs ( TNumType *&  _cfPtr,
TNumType *&  _cfGradPtr,
const size_t &  _optParamSize 
)

Definition at line 472 of file 2/trajectory_simulator.hpp.

template<size_t FuncNr = 0>
void tuw::evaluateCosts ( TNumType *&  _cfPtr,
TNumType *&  _cfGradPtr,
const size_t &  _optParamSize 
)
private

Definition at line 563 of file 2/trajectory_simulator.hpp.

template<std::size_t II = 0, class FuncT , typename... Tp>
constexpr std::enable_if<II == sizeof...(Tp), void>::type tuw::for_each_tuple ( std::tuple< Tp... > &  ,
FuncT   
)
inline

Definition at line 101 of file utils.h.

template<std::size_t II = 0, class FuncT , typename... Tp>
constexpr std::enable_if<II == sizeof...(Tp), void>::type tuw::for_each_tuple_class ( std::tuple< Tp... > &  ,
FuncT &   
)
inline

Definition at line 237 of file 2/trajectory_simulator.hpp.

void tuw::getMinArcLatCacheIdx ( typename std::vector< LatticePointType >::iterator *&  _itMin,
size_t &  _latVecIdx 
)
private

Definition at line 591 of file 2/trajectory_simulator.hpp.

template<class TNumType >
static bool tuw::isSame ( const Eigen::Matrix< TNumType,-1, 1 > &  _optVar0,
const Eigen::Matrix< TNumType,-1, 1 > &  _optVar1 
)
inlinestatic

Definition at line 67 of file trajectory_optimizer.hpp.

template<typename T >
T tuw::normalizeRad ( _x)
inline

Definition at line 64 of file utils.h.

size_t tuw::populatePartLattices ( size_t &  _sizeCosts)
private

Definition at line 508 of file 2/trajectory_simulator.hpp.

void tuw::resizeCosts ( const size_t &  _optParamSize,
const bool &  _simulatingWithGrad 
)
private

Definition at line 526 of file 2/trajectory_simulator.hpp.

void tuw::resizeInternal ( )

Definition at line 496 of file 2/trajectory_simulator.hpp.

void tuw::resizeSimLattice ( const size_t &  _totalPartLatticePtsSize)
private

Definition at line 679 of file 2/trajectory_simulator.hpp.

template<bool useStateSimNm = TUseStateNm, typename std::enable_if<(useStateSimNm)>::type * = nullptr>
void tuw::setXNmDot ( const TNumType &  _arcNow)
private

Definition at line 612 of file 2/trajectory_simulator.hpp.

template<typename T >
constexpr int tuw::signum ( x,
std::false_type  is_signed 
)
inline

Definition at line 45 of file utils.h.

template<typename T >
constexpr int tuw::signum ( x,
std::true_type  is_signed 
)
inline

Definition at line 51 of file utils.h.

template<typename T >
constexpr int tuw::signum ( x)
inline

Definition at line 57 of file utils.h.

void tuw::simulateTrajectory ( const bool &  _saveLatticeStates = false)

Definition at line 448 of file 2/trajectory_simulator.hpp.

void tuw::simulateTrajectoryImpl ( const bool &  _saveLatticeStates = false)

Definition at line 480 of file 2/trajectory_simulator.hpp.

template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void tuw::simulateTrajectoryWithGrad ( const bool &  _saveLatticeStates = false)

Definition at line 458 of file 2/trajectory_simulator.hpp.

tuw::TEST ( TestStateMap  ,
CopyAssignmentOperatorArray   
)

Definition at line 17 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
CopyAssignmentOperatorVector   
)

Definition at line 86 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
CopyAssignmentOperatorTuple   
)

Definition at line 192 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
ExtendedClassInStateMap   
)

Definition at line 300 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedArrayVectorOneLvl   
)

Definition at line 308 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedArraysCompileTimeSize   
)

Definition at line 318 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedVectorsCompileTimeSize   
)

Definition at line 331 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedArraysVectorsCompileTimeSize   
)

Definition at line 342 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedTupleCompileTimeSize   
)

Definition at line 359 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedStateResize   
)

Definition at line 406 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
ResizeWithEmptyVectors   
)

Definition at line 495 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
NestedArraysDataBuffer   
)

Definition at line 530 of file test_state_map.cpp.

tuw::TEST ( TestStateMap  ,
VirtualBase   
)

Definition at line 566 of file test_state_map.cpp.

Variable Documentation

template<std::size_t II = 0, class FuncT , typename... Tp>
constexpr std::enable_if< II<sizeof...(Tp), void>::type for_each_tuple_class(std::tuple<Tp...>& t, FuncT& f){ f[II] = [&t](const auto& _a, const auto& _b, const auto& _c, auto& _d) { std::get<II>t).computeDArcIdPImpl(_a, _b, _c, _d); }; for_each_tuple_class<II + 1, FuncT, Tp...>t, f);}template <std::size_t IIMax, std::size_t II = 0>constexpr inline typename std::enable_if<(II == IIMax), void>::type get_costs_sizes(auto& partLatI, const size_t& _i, auto& _sizeCostsPerPartLattice, auto& _sizeCostsPerType){}template <std::size_t IIMax, std::size_t II = 0>constexpr inline typename std::enable_if<(II < IIMax), void>::type get_costs_sizes(auto& partLatI, const size_t& _i, auto& _sizeCostsPerPartLattice, auto& _sizeCostsPerType){ size_t partLatICostsTypeJ = partLatI.lattice.size() * partLatI.template costFuncsNr<II>); _sizeCostsPerPartLattice[_i] += partLatICostsTypeJ; _sizeCostsPerType[II] += partLatICostsTypeJ; get_costs_sizes<IIMax, II + 1>partLatI, _i, _sizeCostsPerPartLattice, _sizeCostsPerType);}template <typename TNumType, typename TSimType, bool TUseStateNm, template <typename, typename> class... TLatticeTypes>class TrajectorySimulator{public: using StateSimSPtr = std::shared_ptr<TSimType>;public: using StateType = typename TSimType::StateType;public: using StateSPtr = std::shared_ptr<StateType>;public: using StateForSimType = typename TSimType::StateForSimType;public: using LatticePointType = LatticePoint<TNumType, StateType>;public: static constexpr const bool CanComputeStateGrad = !std::is_same<EmptyGradType, typename StateMapBaseTraits<StateType>::StateWithGradNmType>::value;public: static constexpr const size_t CostFuncsTypesNr = std::tuple_element<0, std::tuple<TLatticeTypes<TNumType, TSimType>...> >::type::costFuncsTypesNr();public: TrajectorySimulator() : stateSim_(std::shared_ptr<TSimType>new TSimType)) { for_each_tuple_class(partialLattices_, correctStateGradFunc); for (size_t i = 0; i < gradCostsMap_.size(); ++i) { gradCostsMap_[i] = std::shared_ptr<Eigen::Map<Eigen::Matrix<TNumType, -1, -1, Eigen::RowMajor> > >new Eigen::Map<Eigen::Matrix<TNumType, -1, -1, Eigen::RowMajor> >nullptr, 0, 0)); } }public: TrajectorySimulator(StateSimSPtr& _stateSim) : stateSim_(_stateSim) { for_each_tuple_class(partialLattices_, correctStateGradFunc); for (size_t i = 0; i < gradCostsMap_.size(); ++i) { gradCostsMap_[i] = std::shared_ptr<Eigen::Map<Eigen::Matrix<TNumType, -1, -1, Eigen::RowMajor> > >new Eigen::Map<Eigen::Matrix<TNumType, -1, -1, Eigen::RowMajor> >nullptr, 0, 0)); } } public: StateSimSPtr& stateSim() { return stateSim_; } public: const StateSimSPtr& stateSim() const { return stateSim_; }public: LatticePointType& simLatticeI(const size_t& _i) { return simulationLattice_[_i]; }public: const LatticePointType& simLatticeI(const size_t& _i) const { return simulationLattice_[_i]; }public: size_t simLatticeSize() const { return simulationLatticeActiveSize_; }public: template <template <typename, typename> class TLatticeType> TLatticeType<TNumType, TSimType>& partialLattice() { return std::get<TLatticeType<TNumType, TSimType> >partialLattices_); }public: template <template <typename, typename> class TLatticeType> const TLatticeType<TNumType, TSimType>& partialLattice() const { return std::get<TLatticeType<TNumType, TSimType> >partialLattices_); }public: template <size_t TLatticeIdx> auto& partialLattice() { return std::get<TLatticeIdx>partialLattices_); }public: template <size_t TLatticeIdx> const auto& partialLattice() const { return std::get<TLatticeIdx>partialLattices_); }private: using AdvanceFunction = void (TrajectorySimulator<TNumType, TSimType, TUseStateNm, TLatticeTypes...>::*)(const TNumType&);private: AdvanceFunction advanceFunc;private: void advanceFuncSimEmpty(const TNumType& _arcNow) { }private: void advanceFuncSim(const TNumType& _arcNow) { stateSim_-> tuw::advance(_arcNow)
inline

Definition at line 405 of file 2/trajectory_simulator.hpp.

std::array<std::function<void(const TSimType&, const TNumType&, const size_t&, typename StateMapBaseTraits<typename StateType::StateMapBaseType>::StateGradType&)>, sizeof...(TLatticeTypes)> tuw::correctStateGradFunc

Definition at line 827 of file 2/trajectory_simulator.hpp.

StateMapArray<TNumType, StateMapVector<TNumType, TNumType>, CostFuncsTypesNr> tuw::costs_

Definition at line 830 of file 2/trajectory_simulator.hpp.

StateMapArray<TNumType, StateMapVector<TNumType, StateMapVector<TNumType, TNumType> >, CostFuncsTypesNr> tuw::gradCosts_

Definition at line 833 of file 2/trajectory_simulator.hpp.

std::array<std::shared_ptr<Eigen::Map<Eigen::Matrix<TNumType, -1, -1, Eigen::RowMajor> > >, CostFuncsTypesNr> tuw::gradCostsMap_

Definition at line 841 of file 2/trajectory_simulator.hpp.

constexpr const std::size_t tuw::nrModesMax_ = asInt(FuncEvalMode::ENUM_SIZE) - 1
static

Maximum number of computation modes (except the parametric function itself FUNC). Currently 4 other choices supported.

See also
FuncEvalMode.

Definition at line 71 of file param_func.hpp.

std::tuple<TLatticeTypes<TNumType, TSimType>...> tuw::partialLattices_

Vector containing the ordered sequence of arc parametrizations for each of the used lattices.

Definition at line 822 of file 2/trajectory_simulator.hpp.

bool tuw::simulatingWithGrad
private

Definition at line 417 of file 2/trajectory_simulator.hpp.

std::vector<LatticePointType> tuw::simulationLattice_
private

Lattice requesting each simulated trajectory state.

Definition at line 816 of file 2/trajectory_simulator.hpp.

size_t tuw::simulationLatticeActiveSize_
private

Definition at line 819 of file 2/trajectory_simulator.hpp.

std::array<size_t, sizeof...(TLatticeTypes)> tuw::sizeCosts_
private

Definition at line 845 of file 2/trajectory_simulator.hpp.

std::array<size_t, sizeof...(TLatticeTypes)> tuw::sizeCostsPerPartLattice_
private

Definition at line 848 of file 2/trajectory_simulator.hpp.

std::array<size_t, CostFuncsTypesNr> tuw::sizeCostsPerType_
private

Definition at line 851 of file 2/trajectory_simulator.hpp.

StateSimSPtr tuw::stateSim_
protected

State simulator object.

Definition at line 813 of file 2/trajectory_simulator.hpp.



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