#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::Dynamic > | I |
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > | J |
double | minErr |
double | mu |
double | prevErr |
double | v |
eVector | x64 |
typedef Eigen::Matrix<T,Eigen::Dynamic,1> aruco::LevMarq< T >::eVector |
typedef std::function<void(const eVector &, Eigen::Matrix<T,Eigen::Dynamic,Eigen::Dynamic> &)> aruco::LevMarq< T >::F_z_J |
typedef std::function<void(const eVector &, eVector &)> aruco::LevMarq< T >::F_z_x |
aruco::LevMarq< T >::LevMarq | ( | ) |
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.
maxIters | maximum number of iterations of the algoritm |
minError | to stop the algorithm before reaching the max iterations |
min_step_error_diff | minimum error difference between two iterations. If below this level, then stop. |
tau | parameter 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_epsilon | increment 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. |
void aruco::LevMarq< T >::calcDerivates | ( | const eVector & | z, |
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > & | J, | ||
F_z_x | f_z_x | ||
) |
double aruco::LevMarq< T >::getBestSolution | ( | eVector & | z | ) | |
throw | ( | std::exception | |||
) |
getBestSolution sets in z the best solution up to this moment
z | output |
double aruco::LevMarq< T >::getCurrentSolution | ( | eVector & | z | ) | |
throw | ( | std::exception | |||
) |
void aruco::LevMarq< T >::init | ( | eVector & | z, |
F_z_x | f_z_x | ||
) | |||
throw | ( | std::exception | |
) |
void aruco::LevMarq< T >::setParams | ( | int | maxIters, |
double | minError, | ||
double | min_step_error_diff = 0 , |
||
double | tau = 1 , |
||
double | der_epsilon = 1e-3 |
||
) |
setParams
maxIters | maximum number of iterations of the algoritm |
minError | to stop the algorithm before reaching the max iterations |
min_step_error_diff | minimum error difference between two iterations. If below this level, then stop. |
tau | parameter 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_epsilon | increment 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. |
|
inline |
|
inline |
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
z | function params 1xP to be estimated. input-output. Contains the result of the optimization |
f_z_x | evaluation 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_J | computes 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 |
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
z | function params 1xP to be estimated. input-output. Contains the result of the optimization |
f_z_x | evaluation 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 |
bool aruco::LevMarq< T >::step | ( | F_z_x | f_z_x, |
F_z_J | f_z_J | ||
) | |||
throw | ( | std::exception | |
) |
bool aruco::LevMarq< T >::step | ( | F_z_x | f_z_x | ) | |
throw | ( | std::exception | |||
) |
|
inline |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |