Public Types | Public Member Functions | Private Attributes | List of all members
aruco::LevMarq< T > Class Template Reference

#include <levmarq.h>

Public Types

typedef Eigen::Matrix< T, Eigen::Dynamic, 1 > eVector
 
typedef std::function< void(const eVector &, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > &)> F_z_J
 
typedef std::function< void(const eVector &, eVector &)> F_z_x
 

Public Member Functions

void calcDerivates (const eVector &z, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > &, F_z_x)
 
double getBestSolution (eVector &z) throw (std::exception)
 getBestSolution sets in z the best solution up to this moment More...
 
double getCurrentSolution (eVector &z) throw (std::exception)
 getCurrentSolution returns the current solution More...
 
void init (eVector &z, F_z_x) throw (std::exception)
 Step by step solve mode. More...
 
 LevMarq ()
 
 LevMarq (int maxIters, double minError, double min_step_error_diff=0, double tau=1, double der_epsilon=1e-3)
 Constructor with parms. More...
 
void setParams (int maxIters, double minError, double min_step_error_diff=0, double tau=1, double der_epsilon=1e-3)
 setParams More...
 
void setStepCallBackFunc (std::function< void(const eVector &)> callback)
 
void setStopFunction (std::function< bool(const eVector &)> stop_function)
 
double solve (eVector &z, F_z_x, F_z_J) throw (std::exception)
 solve non linear minimization problem ||F(z)||, where F(z)=f(z) f(z)^t More...
 
double solve (eVector &z, F_z_x) throw (std::exception)
 solve non linear minimization problem ||F(z)||, where F(z)=f(z) f(z)^t More...
 
bool step (F_z_x f_z_x, F_z_J f_z_J) throw (std::exception)
 step gives a step of the search More...
 
bool step (F_z_x f_z_x) throw (std::exception)
 
bool & verbose ()
 

Private Attributes

double _der_epsilon
 
int _maxIters
 
double _min_step_error_diff
 
double _minErrorAllowed
 
std::function< void(const eVector &)> _step_callback
 
std::function< bool(const eVector &)> _stopFunction
 
double _tau
 
bool _verbose
 
eVector curr_z
 
double currErr
 
Eigen::Matrix< T, Eigen::Dynamic, Eigen::DynamicI
 
Eigen::Matrix< T, Eigen::Dynamic, Eigen::DynamicJ
 
double minErr
 
double mu
 
double prevErr
 
double v
 
eVector x64
 

Detailed Description

template<typename T>
class aruco::LevMarq< T >

Definition at line 26 of file levmarq.h.

Member Typedef Documentation

template<typename T>
typedef Eigen::Matrix<T,Eigen::Dynamic,1> aruco::LevMarq< T >::eVector

Definition at line 30 of file levmarq.h.

template<typename T>
typedef std::function<void(const eVector &, Eigen::Matrix<T,Eigen::Dynamic,Eigen::Dynamic> &)> aruco::LevMarq< T >::F_z_J

Definition at line 32 of file levmarq.h.

template<typename T>
typedef std::function<void(const eVector &, eVector &)> aruco::LevMarq< T >::F_z_x

Definition at line 31 of file levmarq.h.

Constructor & Destructor Documentation

template<typename T >
aruco::LevMarq< T >::LevMarq ( )

Definition at line 133 of file levmarq.h.

template<typename T >
aruco::LevMarq< T >::LevMarq ( int  maxIters,
double  minError,
double  min_step_error_diff = 0,
double  tau = 1,
double  der_epsilon = 1e-3 
)

Constructor with parms.

Parameters
maxItersmaximum number of iterations of the algoritm
minErrorto stop the algorithm before reaching the max iterations
min_step_error_diffminimum error difference between two iterations. If below this level, then stop.
tauparameter indicating how near the initial solution is estimated to be to the real one. If 1, it means that it is very far and the first
der_epsilonincrement to calculate the derivate of the evaluation function step will be very short. If near 0, means the opposite. This value is auto calculated in the subsequent iterations.

Definition at line 146 of file levmarq.h.

Member Function Documentation

template<typename T >
void aruco::LevMarq< T >::calcDerivates ( const eVector z,
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > &  J,
F_z_x  f_z_x 
)

Definition at line 171 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::getBestSolution ( eVector z)
throw (std::exception
)

getBestSolution sets in z the best solution up to this moment

Parameters
zoutput
Returns
error of the solution
template<typename T >
double aruco::LevMarq< T >::getCurrentSolution ( eVector z)
throw (std::exception
)

getCurrentSolution returns the current solution

Parameters
zoutput
Returns
error of the solution

Definition at line 264 of file levmarq.h.

template<typename T >
void aruco::LevMarq< T >::init ( eVector z,
F_z_x  f_z_x 
)
throw (std::exception
)

Step by step solve mode.

init initializes the search engine

Parameters
z

Definition at line 196 of file levmarq.h.

template<typename T >
void aruco::LevMarq< T >::setParams ( int  maxIters,
double  minError,
double  min_step_error_diff = 0,
double  tau = 1,
double  der_epsilon = 1e-3 
)

setParams

Parameters
maxItersmaximum number of iterations of the algoritm
minErrorto stop the algorithm before reaching the max iterations
min_step_error_diffminimum error difference between two iterations. If below this level, then stop.
tauparameter indicating how near the initial solution is estimated to be to the real one. If 1, it means that it is very far and the first
der_epsilonincrement to calculate the derivate of the evaluation function step will be very short. If near 0, means the opposite. This value is auto calculated in the subsequent iterations.

Definition at line 160 of file levmarq.h.

template<typename T>
void aruco::LevMarq< T >::setStepCallBackFunc ( std::function< void(const eVector &)>  callback)
inline

Definition at line 110 of file levmarq.h.

template<typename T>
void aruco::LevMarq< T >::setStopFunction ( std::function< bool(const eVector &)>  stop_function)
inline

Definition at line 112 of file levmarq.h.

template<typename T >
double aruco::LevMarq< T >::solve ( eVector z,
F_z_x  f_z_x,
F_z_J  f_J 
)
throw (std::exception
)

solve non linear minimization problem ||F(z)||, where F(z)=f(z) f(z)^t

Parameters
zfunction params 1xP to be estimated. input-output. Contains the result of the optimization
f_z_xevaluation function f(z)=x first parameter : z : input. Data is in double precision as a row vector (1xp) second parameter : x : output. Data must be returned in double
f_Jcomputes the jacobian of f(z) first parameter : z : input. Data is in double precision as a row vector (1xp) second parameter : J : output. Data must be returned in double
Returns
final error

Definition at line 270 of file levmarq.h.

template<typename T >
double aruco::LevMarq< T >::solve ( eVector z,
F_z_x  f_z_x 
)
throw (std::exception
)

solve non linear minimization problem ||F(z)||, where F(z)=f(z) f(z)^t

Automatic jacobian estimation

Parameters
zfunction params 1xP to be estimated. input-output. Contains the result of the optimization
f_z_xevaluation function f(z)=x first parameter : z : input. Data is in double precision as a row vector (1xp) second parameter : x : output. Data must be returned in double
Returns
final error

Definition at line 187 of file levmarq.h.

template<typename T >
bool aruco::LevMarq< T >::step ( F_z_x  f_z_x,
F_z_J  f_z_J 
)
throw (std::exception
)

step gives a step of the search

Parameters
f_z_xerror evaluation function
f_z_JJacobian function
Returns
error of current solution

Definition at line 213 of file levmarq.h.

template<typename T >
bool aruco::LevMarq< T >::step ( F_z_x  f_z_x)
throw (std::exception
)

Definition at line 191 of file levmarq.h.

template<typename T>
bool& aruco::LevMarq< T >::verbose ( )
inline

Definition at line 107 of file levmarq.h.

Member Data Documentation

template<typename T>
double aruco::LevMarq< T >::_der_epsilon
private

Definition at line 117 of file levmarq.h.

template<typename T>
int aruco::LevMarq< T >::_maxIters
private

Definition at line 116 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::_min_step_error_diff
private

Definition at line 117 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::_minErrorAllowed
private

Definition at line 117 of file levmarq.h.

template<typename T>
std::function<void(const eVector &)> aruco::LevMarq< T >::_step_callback
private

Definition at line 124 of file levmarq.h.

template<typename T>
std::function<bool(const eVector &)> aruco::LevMarq< T >::_stopFunction
private

Definition at line 125 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::_tau
private

Definition at line 117 of file levmarq.h.

template<typename T>
bool aruco::LevMarq< T >::_verbose
private

Definition at line 118 of file levmarq.h.

template<typename T>
eVector aruco::LevMarq< T >::curr_z
private

Definition at line 120 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::currErr
private

Definition at line 121 of file levmarq.h.

template<typename T>
Eigen::Matrix<T,Eigen::Dynamic,Eigen::Dynamic> aruco::LevMarq< T >::I
private

Definition at line 122 of file levmarq.h.

template<typename T>
Eigen::Matrix<T,Eigen::Dynamic,Eigen::Dynamic> aruco::LevMarq< T >::J
private

Definition at line 122 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::minErr
private

Definition at line 121 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::mu
private

Definition at line 123 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::prevErr
private

Definition at line 121 of file levmarq.h.

template<typename T>
double aruco::LevMarq< T >::v
private

Definition at line 123 of file levmarq.h.

template<typename T>
eVector aruco::LevMarq< T >::x64
private

Definition at line 120 of file levmarq.h.


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


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:41:03