Classes | Public Member Functions | Public Attributes | Private Attributes | List of all members
tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType > Class Template Reference

#include <agv_diff_drive_v_w_lattices.hpp>

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

Classes

struct  CosSinCache
 

Public Member Functions

void computeDArcIdPImpl (const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
 
void computeDArcIdPImpl (const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
 
void computeLatticeArcsImpl (TSimType &_sim, std::vector< TNumType > &_latticeArcs)
 
void computeLatticeArcsImpl (TSimType &_sim, std::vector< TNumType > &_latticeArcs)
 
const TNumType & dt ()
 
const TNumType & dt ()
 
virtual void precompute (TSimType &_sim) override
 
virtual void precompute (TSimType &_sim) override
 
void setDs (const TNumType &_ds)
 
void setDs (const TNumType &_ds)
 
void setNrPts (const size_t &_nrPts)
 
void setNrPts (const size_t &_nrPts)
 
- Public Member Functions inherited from tuw::LatticeTypeBaseCRTP< LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType... >, TNumType, TSimType, TCostFuncsType... >
void computeLatticeArcs (TSimType &_sim, std::vector< NumType > &_latticeArcs)
 
void computeLatticeStructure (TSimType &_sim, const size_t _latticeIdx)
 
void evaluate (const auto &_x, const size_t &_i, TSimType &_sim, auto &_ansPtr)
 
void evaluate (const auto &_x, const size_t &_i, TSimType &_sim, auto &_ansPtr)
 
void evaluateWithGrad (const auto &_x, const size_t &_i, const auto &_gradX, TSimType &_sim, auto &_ansPtr, auto &_ansGradPtr, const size_t &elSize)
 
void evaluateWithGrad (const auto &_x, const size_t &_i, const auto &_gradX, TSimType &_sim, auto &_ansPtr, auto &_ansGradPtr, const size_t &elSize)
 
 LatticeTypeBaseCRTP ()=default
 
 LatticeTypeBaseCRTP (const LatticeTypeBaseCRTP &)=default
 
 LatticeTypeBaseCRTP (LatticeTypeBaseCRTP &&)=default
 
LatticeTypeBaseCRTPoperator= (const LatticeTypeBaseCRTP &)=default
 
LatticeTypeBaseCRTPoperator= (LatticeTypeBaseCRTP &&)=default
 
virtual ~LatticeTypeBaseCRTP ()=default
 

Public Attributes

std::vector< CosSinCachecosSinCache_
 
TNumType ds_
 
- Public Attributes inherited from tuw::LatticeTypeBaseCRTP< LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType... >, TNumType, TSimType, TCostFuncsType... >
std::vector< LatticePoint< NumType, StateType > > lattice
 

Private Attributes

Eigen::Matrix< TNumType,-1, 1 > dsdp
 
int nrPts_
 
Eigen::Matrix< TNumType,-1, 1 > stateDotCache
 

Additional Inherited Members

- Public Types inherited from tuw::LatticeTypeBaseCRTP< LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType... >, TNumType, TSimType, TCostFuncsType... >
using NumType = TNumType
 
using StateSPtr = std::shared_ptr< StateType >
 
using StateType = typename TSimType::StateType
 
- Static Public Member Functions inherited from tuw::LatticeTypeBaseCRTP< LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType... >, TNumType, TSimType, TCostFuncsType... >
static constexpr const size_t costFuncsNr ()
 
static constexpr const size_t costFuncsNr ()
 
static constexpr const size_t costFuncsTypesNr ()
 

Detailed Description

template<typename TNumType, class TSimType, class... TCostFuncsType>
class tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >

Definition at line 153 of file agv_diff_drive_v_w_lattices.hpp.

Member Function Documentation

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::computeDArcIdPImpl ( const TSimType &  _sim,
const TNumType  _arc,
const size_t &  _lattIdx,
auto &  _dstStateGrad 
)
inline
Todo:
would be nicer to do linear interp between singularity

Definition at line 196 of file edge8_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::computeDArcIdPImpl ( const TSimType &  _sim,
const TNumType  _arc,
const size_t &  _lattIdx,
auto &  _dstStateGrad 
)
inline
Todo:
would be nicer to do linear interp between singularity

Definition at line 197 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::computeLatticeArcsImpl ( TSimType &  _sim,
std::vector< TNumType > &  _latticeArcs 
)
inline

Definition at line 161 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::computeLatticeArcsImpl ( TSimType &  _sim,
std::vector< TNumType > &  _latticeArcs 
)
inline

Definition at line 171 of file edge8_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
const TNumType& tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::dt ( )
inline

Definition at line 236 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
const TNumType& tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::dt ( )
inline

Definition at line 241 of file edge8_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
virtual void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::precompute ( TSimType &  _sim)
inlineoverridevirtual
template<typename TNumType , class TSimType , class... TCostFuncsType>
virtual void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::precompute ( TSimType &  _sim)
inlineoverridevirtual
template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::setDs ( const TNumType &  _ds)
inline

Definition at line 242 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::setDs ( const TNumType &  _ds)
inline

Definition at line 247 of file edge8_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::setNrPts ( const size_t &  _nrPts)
inline

Definition at line 249 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
void tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::setNrPts ( const size_t &  _nrPts)
inline

Definition at line 254 of file edge8_lattices.hpp.

Member Data Documentation

template<typename TNumType , class TSimType , class... TCostFuncsType>
std::vector<CosSinCache> tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::cosSinCache_

Definition at line 168 of file edge8_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
TNumType tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::ds_

Definition at line 255 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
Eigen::Matrix< TNumType,-1, 1 > tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::dsdp
private

Definition at line 261 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
int tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::nrPts_
private

Definition at line 258 of file agv_diff_drive_v_w_lattices.hpp.

template<typename TNumType , class TSimType , class... TCostFuncsType>
Eigen::Matrix< TNumType,-1, 1 > tuw::LatticeTypeStateSimEqDs< TNumType, TSimType, TCostFuncsType >::stateDotCache
private

Definition at line 264 of file agv_diff_drive_v_w_lattices.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:23