Public Member Functions | Public Attributes | Protected Member Functions | List of all members
tuw::CostsEvaluatorBase< Lattice > Class Template Referenceabstract

#include <costs_evaluator.hpp>

Inheritance diagram for tuw::CostsEvaluatorBase< Lattice >:
Inheritance graph
[legend]

Public Member Functions

 CostsEvaluatorBase ()
 
 CostsEvaluatorBase (const CostsEvaluatorBase &)=default
 
 CostsEvaluatorBase (CostsEvaluatorBase &&)=default
 
void evaluateAllCosts ()
 
void evaluateF ()
 
void evaluateG ()
 
void evaluateH ()
 
virtual bool evalValidCostStep (const CostEvaluatorCostType &_arrayType, double _arcNow, size_t &_violatingLatIdx, double &_arcMax)=0
 
bool gIsValid (const double &_boxBound=1e-2) const
 
bool gIsValid (const size_t _Idx, const double &_boxBound=1e-2) const
 
bool hIsValid () const
 
virtual void init (std::vector< std::shared_ptr< Lattice >> &_lattPtr)=0
 
virtual void loadCostFunctions ()=0
 
CostsEvaluatorBaseoperator= (const CostsEvaluatorBase &)=default
 
CostsEvaluatorBaseoperator= (CostsEvaluatorBase &&)=default
 
virtual void resetCostFunctions (const CostEvaluatorCostType &_arrayType)=0
 
virtual ~CostsEvaluatorBase ()=default
 

Public Attributes

double f
 
std::vector< double > g
 
std::vector< double > gradF
 
Eigen::MatrixXd gradG
 
Eigen::MatrixXd gradH
 
std::vector< double > h
 

Protected Member Functions

virtual void computeArrayCost (std::vector< double > &_arr, const CostEvaluatorCostType &_arrayType)=0
 
virtual void computeScalarCost (double &_f)=0
 

Detailed Description

template<typename Lattice>
class tuw::CostsEvaluatorBase< Lattice >

Definition at line 58 of file costs_evaluator.hpp.

Constructor & Destructor Documentation

template<typename Lattice >
tuw::CostsEvaluatorBase< Lattice >::CostsEvaluatorBase ( )
inline

Definition at line 62 of file costs_evaluator.hpp.

template<typename Lattice >
virtual tuw::CostsEvaluatorBase< Lattice >::~CostsEvaluatorBase ( )
virtualdefault
template<typename Lattice >
tuw::CostsEvaluatorBase< Lattice >::CostsEvaluatorBase ( const CostsEvaluatorBase< Lattice > &  )
default
template<typename Lattice >
tuw::CostsEvaluatorBase< Lattice >::CostsEvaluatorBase ( CostsEvaluatorBase< Lattice > &&  )
default

Member Function Documentation

template<typename Lattice >
virtual void tuw::CostsEvaluatorBase< Lattice >::computeArrayCost ( std::vector< double > &  _arr,
const CostEvaluatorCostType _arrayType 
)
protectedpure virtual
template<typename Lattice >
virtual void tuw::CostsEvaluatorBase< Lattice >::computeScalarCost ( double &  _f)
protectedpure virtual
template<typename Lattice >
void tuw::CostsEvaluatorBase< Lattice >::evaluateAllCosts ( )
inline

Definition at line 119 of file costs_evaluator.hpp.

template<typename Lattice >
void tuw::CostsEvaluatorBase< Lattice >::evaluateF ( )
inline

Definition at line 101 of file costs_evaluator.hpp.

template<typename Lattice >
void tuw::CostsEvaluatorBase< Lattice >::evaluateG ( )
inline

Definition at line 113 of file costs_evaluator.hpp.

template<typename Lattice >
void tuw::CostsEvaluatorBase< Lattice >::evaluateH ( )
inline

Definition at line 107 of file costs_evaluator.hpp.

template<typename Lattice >
virtual bool tuw::CostsEvaluatorBase< Lattice >::evalValidCostStep ( const CostEvaluatorCostType _arrayType,
double  _arcNow,
size_t &  _violatingLatIdx,
double &  _arcMax 
)
pure virtual
template<typename Lattice >
bool tuw::CostsEvaluatorBase< Lattice >::gIsValid ( const double &  _boxBound = 1e-2) const
inline

Definition at line 144 of file costs_evaluator.hpp.

template<typename Lattice >
bool tuw::CostsEvaluatorBase< Lattice >::gIsValid ( const size_t  _Idx,
const double &  _boxBound = 1e-2 
) const
inline

Definition at line 157 of file costs_evaluator.hpp.

template<typename Lattice >
bool tuw::CostsEvaluatorBase< Lattice >::hIsValid ( ) const
inline

Definition at line 127 of file costs_evaluator.hpp.

template<typename Lattice >
virtual void tuw::CostsEvaluatorBase< Lattice >::init ( std::vector< std::shared_ptr< Lattice >> &  _lattPtr)
pure virtual
template<typename Lattice >
virtual void tuw::CostsEvaluatorBase< Lattice >::loadCostFunctions ( )
pure virtual
template<typename Lattice >
CostsEvaluatorBase& tuw::CostsEvaluatorBase< Lattice >::operator= ( const CostsEvaluatorBase< Lattice > &  )
default
template<typename Lattice >
CostsEvaluatorBase& tuw::CostsEvaluatorBase< Lattice >::operator= ( CostsEvaluatorBase< Lattice > &&  )
default
template<typename Lattice >
virtual void tuw::CostsEvaluatorBase< Lattice >::resetCostFunctions ( const CostEvaluatorCostType _arrayType)
pure virtual

Member Data Documentation

template<typename Lattice >
double tuw::CostsEvaluatorBase< Lattice >::f

Definition at line 167 of file costs_evaluator.hpp.

template<typename Lattice >
std::vector<double> tuw::CostsEvaluatorBase< Lattice >::g

Definition at line 173 of file costs_evaluator.hpp.

template<typename Lattice >
std::vector<double> tuw::CostsEvaluatorBase< Lattice >::gradF

Definition at line 176 of file costs_evaluator.hpp.

template<typename Lattice >
Eigen::MatrixXd tuw::CostsEvaluatorBase< Lattice >::gradG

Definition at line 182 of file costs_evaluator.hpp.

template<typename Lattice >
Eigen::MatrixXd tuw::CostsEvaluatorBase< Lattice >::gradH

Definition at line 179 of file costs_evaluator.hpp.

template<typename Lattice >
std::vector<double> tuw::CostsEvaluatorBase< Lattice >::h

Definition at line 170 of file costs_evaluator.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