Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Friends | List of all members
tuw::TrajectorySimulator< TNumType, TSimType > Class Template Referenceabstract

#include <trajectory_simulator.h>

Inheritance diagram for tuw::TrajectorySimulator< TNumType, TSimType >:
Inheritance graph
[legend]

Classes

struct  LatticePoint
 Structure containing an evaluation arc and a state pointer. More...
 
struct  LatticePointType
 Structure containing the lattice type afferent to a. More...
 

Public Types

enum  BaseSimLatticeType : signed int {
  BaseSimLatticeType::ARC_BG_BK = -3, BaseSimLatticeType::LATTICE_ARC_EQ_DT = -2, BaseSimLatticeType::LATTICE_ARC_EQ_DS = -1, BaseSimLatticeType::LATTICE_ENUM_SIZE = 3,
  BaseSimLatticeType::ARC_BG_BK = -3, BaseSimLatticeType::LATTICE_ARC_EQ_DT = -2, BaseSimLatticeType::LATTICE_ARC_EQ_DS = -1, BaseSimLatticeType::LATTICE_ENUM_SIZE = 3
}
 Fundamental lattice types. More...
 
enum  BaseSimLatticeType : signed int {
  BaseSimLatticeType::ARC_BG_BK = -3, BaseSimLatticeType::LATTICE_ARC_EQ_DT = -2, BaseSimLatticeType::LATTICE_ARC_EQ_DS = -1, BaseSimLatticeType::LATTICE_ENUM_SIZE = 3,
  BaseSimLatticeType::ARC_BG_BK = -3, BaseSimLatticeType::LATTICE_ARC_EQ_DT = -2, BaseSimLatticeType::LATTICE_ARC_EQ_DS = -1, BaseSimLatticeType::LATTICE_ENUM_SIZE = 3
}
 Fundamental lattice types. More...
 
using CostsEvaluatorClass = CostsEvaluatorBase< TrajectorySimulator::LatticeVec >
 
using CostsEvaluatorClass = CostsEvaluatorBase< TrajectorySimulator::LatticeVec >
 
using LatticeVec = std::vector< LatticePoint >
 
using LatticeVec = std::vector< LatticePoint >
 
using LatticeVecSPtr = std::shared_ptr< std::vector< LatticePoint > >
 
using LatticeVecSPtr = std::shared_ptr< std::vector< LatticePoint >>
 
using LatticeVecSPtrVec = std::vector< std::shared_ptr< std::vector< LatticePoint > > >
 
using LatticeVecSPtrVec = std::vector< std::shared_ptr< std::vector< LatticePoint >>>
 
enum  SimMode { SimMode::ONLINE, SimMode::PRECALC }
 Mode of the simulation. More...
 
using StateForSimType = typename TSimType::StateForSimType
 
using StateSimSPtr = std::shared_ptr< TSimType >
 
using StateSPtr = std::shared_ptr< StateType >
 
using StateType = typename TSimType::StateType
 

Public Member Functions

const double & ds () const
 Const reference to arc parametrization interval used for the equal distance lattice. More...
 
const TNumType & ds () const
 Const reference to arc parametrization interval used for the equal distance lattice. More...
 
double & dsBase ()
 Reference to arc parametrization interval used for the equal distance lattice. More...
 
TNumType & dsBase ()
 Reference to arc parametrization interval used for the equal distance lattice. More...
 
const double & dt () const
 Const reference to arc parametrization interval used for the equal arc-length lattice. More...
 
const TNumType & dt () const
 Const reference to arc parametrization interval used for the equal arc-length lattice. More...
 
double & dtBase ()
 Reference to arc parametrization interval used for the equal arc-length lattice. More...
 
TNumType & dtBase ()
 Reference to arc parametrization interval used for the equal arc-length lattice. More...
 
TrajectorySimulatoroperator= (const TrajectorySimulator &)=default
 
TrajectorySimulatoroperator= (TrajectorySimulator &&)=default
 
TrajectorySimulatoroperator= (const TrajectorySimulator &)=default
 
TrajectorySimulatoroperator= (TrajectorySimulator &&)=default
 
void setBoolDsScale (const bool &_doScale)
 
void setBoolDsScale (const bool &_doScale)
 
void setBoolDtScale (const bool &_doScale)
 
void setBoolDtScale (const bool &_doScale)
 
void setUserDefLattice (const std::vector< std::vector< double * > > &_userDefLattices)
 
void setUserDefLattice (const std::vector< std::vector< TNumType * >> &_userDefLattices)
 
std::vector< LatticePointType > & simLattice ()
 Reference to the lattice that requested each simulated trajectory state. More...
 
const std::vector< LatticePointType > & simLattice () const
 Const reference to the lattice that requested each simulated trajectory state. More...
 
LatticePointTypesimLatticeI (const size_t &_i)
 
const LatticePointTypesimLatticeI (const size_t &_i) const
 
size_t simLatticeSize () const
 
virtual void simulateTrajectory (double _lastValidArc=0)=0
 Simulates (discrete numerical evaluation) an entire trajectory according to the specified intervals and lattices. More...
 
void simulateTrajectory (TNumType _lastValidArc=0)
 
template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void simulateTrajectoryWithGrad (TNumType _lastValidArc=0)
 
StateSimPtr stateSim ()
 Reference of the state simulator object. More...
 
const StateSimPtr stateSim () const
 Const reference of the state simulator object. More...
 
StateSimSPtrstateSim ()
 Reference of the state simulator object. More...
 
const StateSimSPtrstateSim () const
 Const reference of the state simulator object. More...
 
 TrajectorySimulator (StateSimPtr _stateSim)
 
 TrajectorySimulator (StateSimPtr _stateSim, std::unique_ptr< CostsEvaluatorClass > _costsEvaluator)
 
 TrajectorySimulator (const TrajectorySimulator &)=default
 
 TrajectorySimulator (StateSimSPtr &_stateSim)
 
 TrajectorySimulator (TrajectorySimulator &&)=default
 
 TrajectorySimulator (StateSimSPtr &_stateSim, std::unique_ptr< CostsEvaluatorClass > _costsEvaluator)
 
 TrajectorySimulator (const TrajectorySimulator &)=default
 
 TrajectorySimulator (TrajectorySimulator &&)=default
 
void updateUserDefLattice ()
 
void updateUserDefLattice ()
 
virtual ~TrajectorySimulator ()=default
 
virtual ~TrajectorySimulator ()=default
 

Static Public Member Functions

static size_t lattTypeIdx (int _enumIdx)
 Converts shifted (int) lattice index to container (size_t) index. More...
 
static size_t lattTypeIdx (int _enumIdx)
 Converts shifted (int) lattice index to container (size_t) index. More...
 

Public Attributes

std::unique_ptr< CostsEvaluatorClasscostsEvaluator_
 
LatticeVecSPtrVec partLattices_
 Vector containing the ordered sequence of arc parametrizations for each of the used lattices. More...
 
bool simulatingWithGrad
 Simulates (discrete numerical evaluation) an entire trajectory according to the specified intervals and lattices. More...
 
std::vector< LatticePointTypesimulationLattice_
 Lattice requesting each simulated trajectory state. More...
 

Static Public Attributes

static constexpr const bool CanComputeStateGrad
 
static constexpr const std::size_t extArcLatIdxBegin
 

Protected Member Functions

void appendToPartLat (const double &_arcNow, const int &_latticePtType, const std::size_t &_minArcLatCacheIdx)
 Appends the new arc and state pointer to the afferent partial lattice point. More...
 
void appendToPartLat (const TNumType &_arcNow, const int &_latticePtType, const std::size_t &_minArcLatCacheIdx)
 Appends the new arc and state pointer to the afferent partial lattice point. More...
 
void computeScaleDtDs ()
 
void computeScaleDtDs ()
 
void initExtLatticeCache (const double &_minArcLatticeVal)
 Initializes the cached partial lattices index at the highest arc lower than. More...
 
void initExtLatticeCache (const TNumType &_minArcLatticeVal)
 Initializes the cached partial lattices index at the highest arc lower than. More...
 
bool initSimLatticeState0 (const double &_lastValidArc, size_t &_firstLaticeInvalidIdx)
 Initializes the simulation lattice (truncation from the. More...
 
bool initSimLatticeState0 (const TNumType &_lastValidArc, size_t &_firstLaticeInvalidIdx)
 Initializes the simulation lattice (truncation from the. More...
 
bool isEmptyAllExtLattices () const
 Returns true if all extended lattices are empty (the DS lattice as well as user-defined lattices). More...
 
bool isEmptyAllExtLattices () const
 Returns true if all extended lattices are empty (the DS lattice as well as user-defined lattices). More...
 
virtual void populatePartSimLatticesDtOnly (const size_t &_firstLaticeInvalidIdx, double _arcParamMax)
 Performs simulation and populates simulation and partial lattice when only equal dt lattice is enabled. More...
 
void populatePartSimLatticesDtOnly (const size_t &_firstLaticeInvalidIdx, TNumType _arcParamMax)
 Performs simulation and populates simulation and partial lattice when only equal dt lattice is enabled. More...
 
virtual void populatePartSimLatticesGeneral (size_t _firstLaticeInvalidIdx, double _arcParamMax, double _minArcLatticeVal)=0
 Performs simulation and populates simulation and partial lattices in the general case of various enabled lattices. More...
 
void populatePartSimLatticesGeneral (size_t _firstLaticeInvalidIdx, TNumType _arcParamMax, TNumType _minArcLatticeVal)
 Performs simulation and populates simulation and partial lattices in the general case of various enabled lattices. More...
 
void populateTrajSimPartLattice (const size_t &_firstLaticeInvalidIdx)
 Main function that performs resizing, reserving and calls the proper population function. More...
 
void populateTrajSimPartLattice (const size_t &_firstLaticeInvalidIdx)
 Main function that performs resizing, reserving and calls the proper population function. More...
 
void setBeginEndArcsToLattices (const double &_arcBegin, const double &_arcEnd)
 Sets begin and end arcs to all partial lattices on the first and last container positions. More...
 
void setBeginEndArcsToLattices (const TNumType &_arcBegin, const TNumType &_arcEnd)
 Sets begin and end arcs to all partial lattices on the first and last container positions. More...
 
void setBeginStateToLattices (const double &_arcBegin)
 Binds reference to the initial simulated state (at. More...
 
void setBeginStateToLattices (const TNumType &_arcBegin)
 Binds reference to the initial simulated state (at. More...
 
void setEndStateToLattices (const double &_arcEnd)
 Binds reference to the final simulated state (at. More...
 
void setEndStateToLattices (const TNumType &_arcEnd)
 Binds reference to the final simulated state (at. More...
 
void simAppendToSimPartLat (const double &_arcNow, const int &_latticePtType, const std::size_t &_minArcLatCacheIdx)
 Performs a simulation step (if. More...
 
void simAppendToSimPartLat (const TNumType &_arcNow, const int &_latticePtType, const std::size_t &_minArcLatCacheIdx)
 Performs a simulation step (if. More...
 

Static Protected Member Functions

static bool cmpLatticePt (const TrajectorySimulator::LatticePoint &a, const TrajectorySimulator::LatticePoint &b)
 

Protected Attributes

bool canComputeDistLattice_
 Flags if the StateSim object has access to the StateSimDist functionality. More...
 
std::vector< int > partLatIdxCache_
 Vector containing cached container indices for each partial lattice related to the the highest arc lower than the current evaluated arc. More...
 
bool scaleDs_
 
bool scaleDt_
 
StateSimPtr stateSim_
 State simulator object. More...
 
StateSimSPtr stateSim_
 State simulator object. More...
 

Private Types

using AdvanceFunction = void(TrajectorySimulator< TNumType, TSimType >::*)(const TNumType &)
 

Private Member Functions

void advanceFuncSim (const TNumType &_arcNow)
 
template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void advanceFuncSimGrad (const TNumType &_arcNow)
 
auto & dtIdpCf (const size_t _i, const TNumType &_arcNow, const int &_latticePtType) const
 
auto & dtIdpNm (const size_t _i, const TNumType &_arcNow, const int &_latticePtType) const
 
size_t getMinArcLatCacheIdx () const
 
void simulateTrajectoryImpl (TNumType _lastValidArc)
 

Static Private Member Functions

template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void copyDataFromSimStateToState (const TSimState &_simState, TState &_state)
 
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void copyDataFromSimStateToState (const TSimState &_simState, TState &_state)
 
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void copyDataFromStateToSimState (const TState &_state, TSimState &_simState)
 
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void copyDataFromStateToSimState (const TState &_state, TSimState &_simState)
 
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void copyStructureFromSimStateToState (const TSimState &_simState, TState &_state)
 
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void copyStructureFromSimStateToState (const TSimState &_simState, TState &_state)
 

Private Attributes

AdvanceFunction advanceFunc
 
double ds_
 Arc parametrization interval used for the equal distance lattice. More...
 
TNumType ds_
 Arc parametrization interval used for the equal distance lattice. More...
 
double dsBase_
 
TNumType dsBase_
 
double dt_
 Arc parametrization interval used for the equal arc-length lattice. More...
 
TNumType dt_
 Arc parametrization interval used for the equal arc-length lattice. More...
 
double dtBase_
 
TNumType dtBase_
 
bool firstTime_
 
size_t simAppendIdx_
 
size_t simulationLatticeActiveSize_
 
std::vector< std::vector< double * > > userDefPartLattices_
 
std::vector< std::vector< TNumType * > > userDefPartLattices_
 

Friends

class TrajectorySimGrade
 

Detailed Description

template<typename TNumType, typename TSimType>
class tuw::TrajectorySimulator< TNumType, TSimType >

Definition at line 51 of file trajectory_simulator.h.

Member Typedef Documentation

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::AdvanceFunction = void (TrajectorySimulator<TNumType, TSimType>::*)(const TNumType&)
private

Definition at line 426 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::CostsEvaluatorClass = CostsEvaluatorBase<TrajectorySimulator::LatticeVec>

Definition at line 118 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::CostsEvaluatorClass = CostsEvaluatorBase<TrajectorySimulator::LatticeVec>

Definition at line 127 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::LatticeVec = std::vector<LatticePoint>

Definition at line 96 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::LatticeVec = std::vector<LatticePoint>

Definition at line 105 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::LatticeVecSPtr = std::shared_ptr<std::vector<LatticePoint> >

Definition at line 97 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::LatticeVecSPtr = std::shared_ptr<std::vector<LatticePoint>>

Definition at line 106 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::LatticeVecSPtrVec = std::vector<std::shared_ptr<std::vector<LatticePoint> > >

Definition at line 98 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::LatticeVecSPtrVec = std::vector<std::shared_ptr<std::vector<LatticePoint>>>

Definition at line 107 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::StateForSimType = typename TSimType::StateForSimType

Definition at line 64 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::StateSimSPtr = std::shared_ptr<TSimType>

Definition at line 55 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::StateSPtr = std::shared_ptr<StateType>

Definition at line 61 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
using tuw::TrajectorySimulator< TNumType, TSimType >::StateType = typename TSimType::StateType

Definition at line 58 of file trajectory_simulator.hpp.

Member Enumeration Documentation

template<typename TNumType , typename TSimType >
enum tuw::TrajectorySimulator::BaseSimLatticeType : signed int
strong

Fundamental lattice types.

Enumerator
ARC_BG_BK 
LATTICE_ARC_EQ_DT 

begin and end of the simulation lattice

LATTICE_ARC_EQ_DS 

equal arc lattice

LATTICE_ENUM_SIZE 

equal distance lattice

ARC_BG_BK 
LATTICE_ARC_EQ_DT 

begin and end of the simulation lattice

LATTICE_ARC_EQ_DS 

equal arc lattice

LATTICE_ENUM_SIZE 

equal distance lattice

Definition at line 66 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
enum tuw::TrajectorySimulator::BaseSimLatticeType : signed int
strong

Fundamental lattice types.

Enumerator
ARC_BG_BK 
LATTICE_ARC_EQ_DT 

begin and end of the simulation lattice

LATTICE_ARC_EQ_DS 

equal arc lattice

LATTICE_ENUM_SIZE 

equal distance lattice

ARC_BG_BK 
LATTICE_ARC_EQ_DT 

begin and end of the simulation lattice

LATTICE_ARC_EQ_DS 

equal arc lattice

LATTICE_ENUM_SIZE 

equal distance lattice

Definition at line 73 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
enum tuw::TrajectorySimulator::SimMode
strong

Mode of the simulation.

Enumerator
ONLINE 
PRECALC 

Online evaluation. In this mode, every trajectory compuation step is performed incrementally for each

lattice point: choosing the lattices order, simulation, grading (efficient when expected to interrupt simulation prematurely) > Precomputed evaluation. In this mode, every sub-problem is executed entirely for all lattice points: choosing the lattices order, simulation, grading (efficient when full trajectory computation is desired)

Definition at line 56 of file trajectory_simulator.h.

Constructor & Destructor Documentation

template<typename TNumType , typename TSimType >
TrajectorySimulator::TrajectorySimulator ( StateSimPtr  _stateSim)

Definition at line 45 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( StateSimPtr  _stateSim,
std::unique_ptr< CostsEvaluatorClass _costsEvaluator 
)
template<typename TNumType , typename TSimType >
virtual tuw::TrajectorySimulator< TNumType, TSimType >::~TrajectorySimulator ( )
virtualdefault
template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( const TrajectorySimulator< TNumType, TSimType > &  )
default
template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( TrajectorySimulator< TNumType, TSimType > &&  )
default
template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( StateSimSPtr _stateSim)
inline

Definition at line 131 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( StateSimSPtr _stateSim,
std::unique_ptr< CostsEvaluatorClass _costsEvaluator 
)
inline

Definition at line 150 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
virtual tuw::TrajectorySimulator< TNumType, TSimType >::~TrajectorySimulator ( )
virtualdefault
template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( const TrajectorySimulator< TNumType, TSimType > &  )
default
template<typename TNumType , typename TSimType >
tuw::TrajectorySimulator< TNumType, TSimType >::TrajectorySimulator ( TrajectorySimulator< TNumType, TSimType > &&  )
default

Member Function Documentation

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::advanceFuncSim ( const TNumType &  _arcNow)
inlineprivate

Definition at line 430 of file trajectory_simulator.hpp.

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

Definition at line 438 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::appendToPartLat ( const double &  _arcNow,
const int &  _latticePtType,
const std::size_t &  _minArcLatCacheIdx 
)
protected

Appends the new arc and state pointer to the afferent partial lattice point.

Definition at line 113 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::appendToPartLat ( const TNumType &  _arcNow,
const int &  _latticePtType,
const std::size_t &  _minArcLatCacheIdx 
)
inlineprotected

Appends the new arc and state pointer to the afferent partial lattice point.

Definition at line 636 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
static bool tuw::TrajectorySimulator< TNumType, TSimType >::cmpLatticePt ( const TrajectorySimulator< TNumType, TSimType >::LatticePoint a,
const TrajectorySimulator< TNumType, TSimType >::LatticePoint b 
)
inlinestaticprotected

Definition at line 686 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::computeScaleDtDs ( )
protected

Definition at line 288 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::computeScaleDtDs ( )
inlineprotected

Definition at line 837 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void tuw::TrajectorySimulator< TNumType, TSimType >::copyDataFromSimStateToState ( const TSimState &  _simState,
TState &  _state 
)
inlinestaticprivate

Definition at line 472 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void tuw::TrajectorySimulator< TNumType, TSimType >::copyDataFromSimStateToState ( const TSimState &  _simState,
TState &  _state 
)
inlinestaticprivate

Definition at line 481 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void tuw::TrajectorySimulator< TNumType, TSimType >::copyDataFromStateToSimState ( const TState &  _state,
TSimState &  _simState 
)
inlinestaticprivate

Definition at line 512 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void tuw::TrajectorySimulator< TNumType, TSimType >::copyDataFromStateToSimState ( const TState &  _state,
TSimState &  _simState 
)
inlinestaticprivate

Definition at line 521 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(!canComputeStateGrad)>::type * = nullptr>
static void tuw::TrajectorySimulator< TNumType, TSimType >::copyStructureFromSimStateToState ( const TSimState &  _simState,
TState &  _state 
)
inlinestaticprivate

Definition at line 492 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<typename TSimState , typename TState , bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
static void tuw::TrajectorySimulator< TNumType, TSimType >::copyStructureFromSimStateToState ( const TSimState &  _simState,
TState &  _state 
)
inlinestaticprivate

Definition at line 501 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
const double & TrajectorySimulator::ds ( ) const

Const reference to arc parametrization interval used for the equal distance lattice.

Definition at line 325 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
const TNumType& tuw::TrajectorySimulator< TNumType, TSimType >::ds ( ) const
inline

Const reference to arc parametrization interval used for the equal distance lattice.

Definition at line 204 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
double & TrajectorySimulator::dsBase ( )

Reference to arc parametrization interval used for the equal distance lattice.

Definition at line 321 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
TNumType& tuw::TrajectorySimulator< TNumType, TSimType >::dsBase ( )
inline

Reference to arc parametrization interval used for the equal distance lattice.

Definition at line 198 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
const double & TrajectorySimulator::dt ( ) const

Const reference to arc parametrization interval used for the equal arc-length lattice.

Definition at line 317 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
const TNumType& tuw::TrajectorySimulator< TNumType, TSimType >::dt ( ) const
inline

Const reference to arc parametrization interval used for the equal arc-length lattice.

Definition at line 192 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
double & TrajectorySimulator::dtBase ( )

Reference to arc parametrization interval used for the equal arc-length lattice.

Definition at line 313 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
TNumType& tuw::TrajectorySimulator< TNumType, TSimType >::dtBase ( )
inline

Reference to arc parametrization interval used for the equal arc-length lattice.

Definition at line 186 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
auto& tuw::TrajectorySimulator< TNumType, TSimType >::dtIdpCf ( const size_t  _i,
const TNumType &  _arcNow,
const int &  _latticePtType 
) const
inlineprivate

Definition at line 457 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
auto& tuw::TrajectorySimulator< TNumType, TSimType >::dtIdpNm ( const size_t  _i,
const TNumType &  _arcNow,
const int &  _latticePtType 
) const
inlineprivate

Definition at line 444 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
size_t tuw::TrajectorySimulator< TNumType, TSimType >::getMinArcLatCacheIdx ( ) const
inlineprivate

Definition at line 406 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::initExtLatticeCache ( const double &  _minArcLatticeVal)
protected

Initializes the cached partial lattices index at the highest arc lower than.

Parameters
_minArcLatticeVal.

Definition at line 190 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::initExtLatticeCache ( const TNumType &  _minArcLatticeVal)
inlineprotected

Initializes the cached partial lattices index at the highest arc lower than.

Parameters
_minArcLatticeVal.

Definition at line 719 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
bool TrajectorySimulator::initSimLatticeState0 ( const double &  _lastValidArc,
size_t &  _firstLaticeInvalidIdx 
)
protected

Initializes the simulation lattice (truncation from the.

Parameters
_firstLaticeInvalidIdx)and sets the state simulator inital state (at
_lastValidArc).

Definition at line 164 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::initSimLatticeState0 ( const TNumType &  _lastValidArc,
size_t &  _firstLaticeInvalidIdx 
)
inlineprotected

Initializes the simulation lattice (truncation from the.

Parameters
_firstLaticeInvalidIdx)and sets the state simulator inital state (at
_lastValidArc).

Definition at line 694 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
bool TrajectorySimulator::isEmptyAllExtLattices ( ) const
protected

Returns true if all extended lattices are empty (the DS lattice as well as user-defined lattices).

Definition at line 274 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::isEmptyAllExtLattices ( ) const
inlineprotected

Returns true if all extended lattices are empty (the DS lattice as well as user-defined lattices).

Definition at line 816 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
size_t TrajectorySimulator::lattTypeIdx ( int  _enumIdx)
static

Converts shifted (int) lattice index to container (size_t) index.

See also
Parameters
BaseSimLatticeType.

Definition at line 269 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
static size_t tuw::TrajectorySimulator< TNumType, TSimType >::lattTypeIdx ( int  _enumIdx)
inlinestatic

Converts shifted (int) lattice index to container (size_t) index.

See also
Parameters
BaseSimLatticeType.

Definition at line 831 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
TrajectorySimulator& tuw::TrajectorySimulator< TNumType, TSimType >::operator= ( const TrajectorySimulator< TNumType, TSimType > &  )
default
template<typename TNumType , typename TSimType >
TrajectorySimulator& tuw::TrajectorySimulator< TNumType, TSimType >::operator= ( TrajectorySimulator< TNumType, TSimType > &&  )
default
template<typename TNumType , typename TSimType >
TrajectorySimulator& tuw::TrajectorySimulator< TNumType, TSimType >::operator= ( const TrajectorySimulator< TNumType, TSimType > &  )
default
template<typename TNumType , typename TSimType >
TrajectorySimulator& tuw::TrajectorySimulator< TNumType, TSimType >::operator= ( TrajectorySimulator< TNumType, TSimType > &&  )
default
template<typename TNumType , typename TSimType >
void TrajectorySimulator::populatePartSimLatticesDtOnly ( const size_t &  _firstLaticeInvalidIdx,
double  _arcParamMax 
)
protectedvirtual

Performs simulation and populates simulation and partial lattice when only equal dt lattice is enabled.

Reimplemented in tuw::TrajectorySimulatorOnline.

Definition at line 254 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::populatePartSimLatticesDtOnly ( const size_t &  _firstLaticeInvalidIdx,
TNumType  _arcParamMax 
)
inlineprotected

Performs simulation and populates simulation and partial lattice when only equal dt lattice is enabled.

Definition at line 348 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
virtual void tuw::TrajectorySimulator< TNumType, TSimType >::populatePartSimLatticesGeneral ( size_t  _firstLaticeInvalidIdx,
double  _arcParamMax,
double  _minArcLatticeVal 
)
protectedpure virtual

Performs simulation and populates simulation and partial lattices in the general case of various enabled lattices.

Implemented in tuw::TrajectorySimulatorPrecalc.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::populatePartSimLatticesGeneral ( size_t  _firstLaticeInvalidIdx,
TNumType  _arcParamMax,
TNumType  _minArcLatticeVal 
)
inlineprotected

Performs simulation and populates simulation and partial lattices in the general case of various enabled lattices.

Definition at line 365 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::populateTrajSimPartLattice ( const size_t &  _firstLaticeInvalidIdx)
protected

Main function that performs resizing, reserving and calls the proper population function.

Definition at line 212 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::populateTrajSimPartLattice ( const size_t &  _firstLaticeInvalidIdx)
inlineprotected

Main function that performs resizing, reserving and calls the proper population function.

Definition at line 742 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::setBeginEndArcsToLattices ( const double &  _arcBegin,
const double &  _arcEnd 
)
protected

Sets begin and end arcs to all partial lattices on the first and last container positions.

Definition at line 147 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setBeginEndArcsToLattices ( const TNumType &  _arcBegin,
const TNumType &  _arcEnd 
)
inlineprotected

Sets begin and end arcs to all partial lattices on the first and last container positions.

Definition at line 674 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::setBeginStateToLattices ( const double &  _arcBegin)
protected

Binds reference to the initial simulated state (at.

Parameters
_arcBegin)to all partial lattices.

Definition at line 121 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setBeginStateToLattices ( const TNumType &  _arcBegin)
inlineprotected

Binds reference to the initial simulated state (at.

Parameters
_arcBegin)to all partial lattices.

Definition at line 644 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::setBoolDsScale ( const bool &  _doScale)

Definition at line 308 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setBoolDsScale ( const bool &  _doScale)
inline

Definition at line 179 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::setBoolDtScale ( const bool &  _doScale)

Definition at line 304 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setBoolDtScale ( const bool &  _doScale)
inline

Definition at line 173 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::setEndStateToLattices ( const double &  _arcEnd)
protected

Binds reference to the final simulated state (at.

Parameters
_arcEnd)to all partial lattices.

Definition at line 133 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setEndStateToLattices ( const TNumType &  _arcEnd)
inlineprotected

Binds reference to the final simulated state (at.

Parameters
_arcEnd)to all partial lattices.

Definition at line 657 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setUserDefLattice ( const std::vector< std::vector< double * > > &  _userDefLattices)
Todo:
documentation
template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::setUserDefLattice ( const std::vector< std::vector< TNumType * >> &  _userDefLattices)
inline
Todo:
documentation

Definition at line 222 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::simAppendToSimPartLat ( const double &  _arcNow,
const int &  _latticePtType,
const std::size_t &  _minArcLatCacheIdx 
)
protected

Performs a simulation step (if.

Parameters
_arcNowis different than last simulated arc) and appends the new arc and state pointer to the afferent partial lattice point.

Definition at line 102 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::simAppendToSimPartLat ( const TNumType &  _arcNow,
const int &  _latticePtType,
const std::size_t &  _minArcLatCacheIdx 
)
inlineprotected

Performs a simulation step (if.

Parameters
_arcNowis different than last simulated arc) and appends the new arc and state pointer to the afferent partial lattice point.

Definition at line 532 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
vector< TrajectorySimulator::LatticePointType > & TrajectorySimulator::simLattice ( )

Reference to the lattice that requested each simulated trajectory state.

Definition at line 337 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
const vector< TrajectorySimulator::LatticePointType > & TrajectorySimulator::simLattice ( ) const

Const reference to the lattice that requested each simulated trajectory state.

Definition at line 341 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
LatticePointType& tuw::TrajectorySimulator< TNumType, TSimType >::simLatticeI ( const size_t &  _i)
inline

Definition at line 854 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
const LatticePointType& tuw::TrajectorySimulator< TNumType, TSimType >::simLatticeI ( const size_t &  _i) const
inline

Definition at line 860 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
size_t tuw::TrajectorySimulator< TNumType, TSimType >::simLatticeSize ( ) const
inline

Definition at line 866 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
virtual void tuw::TrajectorySimulator< TNumType, TSimType >::simulateTrajectory ( double  _lastValidArc = 0)
pure virtual

Simulates (discrete numerical evaluation) an entire trajectory according to the specified intervals and lattices.

Parameters
_lastValidArcSpecifies the last arc at which the previous simulation was still valid. Setting it non-zero is beneficial if already computed (in memory) trajStates() are guaranteed to not have changed. Thus, it allows the function to simulate only portions of the entire arc parametrization domain.

Implemented in tuw::TrajectorySimulatorOnline, and tuw::TrajectorySimulatorPrecalc.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::simulateTrajectory ( TNumType  _lastValidArc = 0)
inline

Definition at line 266 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::simulateTrajectoryImpl ( TNumType  _lastValidArc)
inlineprivate

Definition at line 284 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
template<bool canComputeStateGrad = CanComputeStateGrad, typename std::enable_if<(canComputeStateGrad)>::type * = nullptr>
void tuw::TrajectorySimulator< TNumType, TSimType >::simulateTrajectoryWithGrad ( TNumType  _lastValidArc = 0)
inline

Definition at line 276 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
StateSimPtr TrajectorySimulator::stateSim ( )

Reference of the state simulator object.

Definition at line 329 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
const StateSimPtr TrajectorySimulator::stateSim ( ) const

Const reference of the state simulator object.

Definition at line 333 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
StateSimSPtr& tuw::TrajectorySimulator< TNumType, TSimType >::stateSim ( )
inline

Reference of the state simulator object.

Definition at line 210 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
const StateSimSPtr& tuw::TrajectorySimulator< TNumType, TSimType >::stateSim ( ) const
inline

Const reference of the state simulator object.

Definition at line 216 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
void TrajectorySimulator::updateUserDefLattice ( )

Definition at line 90 of file trajectory_simulator.cpp.

template<typename TNumType , typename TSimType >
void tuw::TrajectorySimulator< TNumType, TSimType >::updateUserDefLattice ( )
inline

Definition at line 243 of file trajectory_simulator.hpp.

Friends And Related Function Documentation

template<typename TNumType , typename TSimType >
TrajectorySimGrade
friend

Definition at line 278 of file trajectory_simulator.h.

Member Data Documentation

template<typename TNumType , typename TSimType >
AdvanceFunction tuw::TrajectorySimulator< TNumType, TSimType >::advanceFunc
private

Definition at line 427 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::canComputeDistLattice_
protected

Flags if the StateSim object has access to the StateSimDist functionality.

Definition at line 252 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
constexpr const bool tuw::TrajectorySimulator< TNumType, TSimType >::CanComputeStateGrad
static
Initial value:
=
!std::is_same<EmptyGradType, typename StateMapBaseTraits<StateType>::StateWithGradNmType>::value

Definition at line 67 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
std::unique_ptr< CostsEvaluatorClass > tuw::TrajectorySimulator< TNumType, TSimType >::costsEvaluator_

Definition at line 276 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
double tuw::TrajectorySimulator< TNumType, TSimType >::ds_
private

Arc parametrization interval used for the equal distance lattice.

Definition at line 258 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
TNumType tuw::TrajectorySimulator< TNumType, TSimType >::ds_
private

Arc parametrization interval used for the equal distance lattice.

Definition at line 895 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
double tuw::TrajectorySimulator< TNumType, TSimType >::dsBase_
private

Definition at line 264 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
TNumType tuw::TrajectorySimulator< TNumType, TSimType >::dsBase_
private

Definition at line 901 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
double tuw::TrajectorySimulator< TNumType, TSimType >::dt_
private

Arc parametrization interval used for the equal arc-length lattice.

Definition at line 255 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
TNumType tuw::TrajectorySimulator< TNumType, TSimType >::dt_
private

Arc parametrization interval used for the equal arc-length lattice.

Definition at line 892 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
double tuw::TrajectorySimulator< TNumType, TSimType >::dtBase_
private

Definition at line 261 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
TNumType tuw::TrajectorySimulator< TNumType, TSimType >::dtBase_
private

Definition at line 898 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
static constexpr const std::size_t tuw::TrajectorySimulator< TNumType, TSimType >::extArcLatIdxBegin
static
template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::firstTime_
private

Definition at line 916 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
std::vector< int > tuw::TrajectorySimulator< TNumType, TSimType >::partLatIdxCache_
protected

Vector containing cached container indices for each partial lattice related to the the highest arc lower than the current evaluated arc.

Definition at line 249 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
LatticeVecSPtrVec tuw::TrajectorySimulator< TNumType, TSimType >::partLattices_

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

Definition at line 245 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::scaleDs_
protected

Definition at line 270 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::scaleDt_
protected

Definition at line 267 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
size_t tuw::TrajectorySimulator< TNumType, TSimType >::simAppendIdx_
private

Definition at line 913 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
bool tuw::TrajectorySimulator< TNumType, TSimType >::simulatingWithGrad

Simulates (discrete numerical evaluation) an entire trajectory according to the specified intervals and lattices.

Parameters
_lastValidArcSpecifies the last arc at which the previous simulation was still valid. Setting it non-zero is beneficial if already computed (in memory) trajStates() are guaranteed to not have changed. Thus, it allows the function to simulate only portions of the entire arc parametrization domain.

Definition at line 263 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
std::vector< LatticePointType > tuw::TrajectorySimulator< TNumType, TSimType >::simulationLattice_

Lattice requesting each simulated trajectory state.

Definition at line 242 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
size_t tuw::TrajectorySimulator< TNumType, TSimType >::simulationLatticeActiveSize_
private

Definition at line 879 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
StateSimPtr tuw::TrajectorySimulator< TNumType, TSimType >::stateSim_
protected

State simulator object.

Definition at line 239 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
StateSimSPtr tuw::TrajectorySimulator< TNumType, TSimType >::stateSim_
protected

State simulator object.

Definition at line 873 of file trajectory_simulator.hpp.

template<typename TNumType , typename TSimType >
std::vector<std::vector<double*> > tuw::TrajectorySimulator< TNumType, TSimType >::userDefPartLattices_
private

Definition at line 273 of file trajectory_simulator.h.

template<typename TNumType , typename TSimType >
std::vector<std::vector<TNumType*> > tuw::TrajectorySimulator< TNumType, TSimType >::userDefPartLattices_
private

Definition at line 910 of file trajectory_simulator.hpp.


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


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