Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap > Class Template Reference

#include <trajectory_optimizer.hpp>

Inheritance diagram for tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >:
Inheritance graph
[legend]

Public Member Functions

const Eigen::Matrix< TNumType,-1, 1 > & cachedCosts (const size_t &_i) const
 
const Eigen::Matrix< TNumType,-1,-1 > & cachedGradCosts (const size_t &_i) const
 
auto & costs ()
 
 CostsEvaluatorCached ()
 
bool evaluateCosts (const Eigen::Matrix< TNumType,-1, 1 > &_x, const OptCacheType &_cacheType=OptCacheType::LAST1)
 
bool evaluateCostsWithGrad (const Eigen::Matrix< TNumType,-1, 1 > &_x, const OptCacheType &_cacheType=OptCacheType::LAST1)
 
void getOptVar (Eigen::Matrix< TNumType,-1, 1 > &_optVarExt)
 
auto & gradCosts ()
 

Private Member Functions

void setOptVar (const Eigen::Matrix< TNumType,-1, 1 > &_optVarExt)
 

Private Attributes

std::array< std::array< std::shared_ptr< Eigen::Matrix< TNumType,-1, 1 > >, TTrajSim::CostFuncsTypesNr >, asInt(OptCacheType::ENUM_SIZE)> constCache_
 
std::array< std::array< std::shared_ptr< Eigen::Matrix< TNumType,-1,-1 > >, TTrajSim::CostFuncsTypesNr >, asInt(OptCacheType::ENUM_SIZE)> gradConstrCache_
 
size_t idxCacheGradLast_
 
size_t idxCacheLast_
 
size_t idxEvalFunc_
 
size_t idxEvalGrad_
 
std::array< std::shared_ptr< Eigen::Matrix< TNumType,-1, 1 > >, asInt(OptCacheType::ENUM_SIZE)> xCacheConstr_
 
std::array< std::shared_ptr< Eigen::Matrix< TNumType,-1, 1 > >, asInt(OptCacheType::ENUM_SIZE)> xCacheGradConstr_
 

Friends

template<class TNumType2 , class TTrajSimJGH2 , class TTrajSimJ2 , class TTrajSimG2 , class TTrajSimH2 , class TMyParamType2 , template< class, class > class TOptVarMap2>
class TrajectoryOptimizer
 

Detailed Description

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
class tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >

Todo:
return references to the cached stuff, do not copy them in the costs lolz :D i.e. you copy ( store ) only when you see new stuff (to cache) but always return the cache data

Definition at line 98 of file trajectory_optimizer.hpp.

Constructor & Destructor Documentation

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::CostsEvaluatorCached ( )
inline

Definition at line 101 of file trajectory_optimizer.hpp.

Member Function Documentation

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
const Eigen::Matrix<TNumType, -1, 1>& tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::cachedCosts ( const size_t &  _i) const
inline

Definition at line 199 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
const Eigen::Matrix<TNumType, -1, -1>& tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::cachedGradCosts ( const size_t &  _i) const
inline

Definition at line 205 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
auto& tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::costs ( )
inline

Definition at line 116 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
bool tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::evaluateCosts ( const Eigen::Matrix< TNumType,-1, 1 > &  _x,
const OptCacheType _cacheType = OptCacheType::LAST1 
)
inline

Definition at line 128 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
bool tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::evaluateCostsWithGrad ( const Eigen::Matrix< TNumType,-1, 1 > &  _x,
const OptCacheType _cacheType = OptCacheType::LAST1 
)
inline

Definition at line 161 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
void tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::getOptVar ( Eigen::Matrix< TNumType,-1, 1 > &  _optVarExt)
inline

Definition at line 211 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
auto& tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::gradCosts ( )
inline

Definition at line 122 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
void tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::setOptVar ( const Eigen::Matrix< TNumType,-1, 1 > &  _optVarExt)
inlineprivate

Definition at line 217 of file trajectory_optimizer.hpp.

Friends And Related Function Documentation

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
template<class TNumType2 , class TTrajSimJGH2 , class TTrajSimJ2 , class TTrajSimG2 , class TTrajSimH2 , class TMyParamType2 , template< class, class > class TOptVarMap2>
friend class TrajectoryOptimizer
friend

Definition at line 250 of file trajectory_optimizer.hpp.

Member Data Documentation

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
std::array<std::array<std::shared_ptr<Eigen::Matrix<TNumType, -1, 1> >, TTrajSim::CostFuncsTypesNr>, asInt(OptCacheType::ENUM_SIZE)> tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::constCache_
private

Definition at line 230 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
std::array<std::array<std::shared_ptr<Eigen::Matrix<TNumType, -1, -1> >, TTrajSim::CostFuncsTypesNr>, asInt(OptCacheType::ENUM_SIZE)> tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::gradConstrCache_
private

Definition at line 234 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
size_t tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::idxCacheGradLast_
private

Definition at line 240 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
size_t tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::idxCacheLast_
private

Definition at line 237 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
size_t tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::idxEvalFunc_
private

Definition at line 243 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
size_t tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::idxEvalGrad_
private

Definition at line 246 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
std::array<std::shared_ptr<Eigen::Matrix<TNumType, -1, 1> >, asInt(OptCacheType::ENUM_SIZE)> tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::xCacheConstr_
private

Definition at line 223 of file trajectory_optimizer.hpp.

template<class TNumType, class TTrajSim, class TMyParamType, template< class, class > class TOptVarMap>
std::array<std::shared_ptr<Eigen::Matrix<TNumType, -1, 1> >, asInt(OptCacheType::ENUM_SIZE)> tuw::CostsEvaluatorCached< TNumType, TTrajSim, TMyParamType, TOptVarMap >::xCacheGradConstr_
private

Definition at line 226 of file trajectory_optimizer.hpp.


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


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