Template Class LevMarq

Class Documentation

template<typename T>
class LevMarq

Public Types

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

Public Functions

LevMarq()
LevMarq(int maxIters, double minError, double min_step_error_diff = 0, double tau = 1, double der_epsilon = 1e-3)

Constructor with parms.

Parameters:
  • 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 setParams(int maxIters, double minError, double min_step_error_diff = 0, double tau = 1, double der_epsilon = 1e-3)

setParams

Parameters:
  • 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.

double solve(eVector &z, F_z_x, F_z_J)

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

Parameters:
  • 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

Returns:

final error

void init(eVector &z, F_z_x)

Step by step solve mode.

init initializes the search engine

Parameters:

z

bool step(F_z_x f_z_x, F_z_J f_z_J)

step gives a step of the search

Parameters:
  • f_z_x – error evaluation function

  • f_z_J – Jacobian function

Returns:

error of current solution

bool step(F_z_x f_z_x)
double getCurrentSolution(eVector &z)

getCurrentSolution returns the current solution

Parameters:

z – output

Returns:

error of the solution

double getBestSolution(eVector &z)

getBestSolution sets in z the best solution up to this moment

Parameters:

z – output

Returns:

error of the solution

double solve(eVector &z, F_z_x)

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

Automatic jacobian estimation

Parameters:
  • 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

Returns:

final error

inline bool &verbose()
inline void setStepCallBackFunc(std::function<void(const eVector&)> callback)
inline void setStopFunction(std::function<bool(const eVector&)> stop_function)
void calcDerivates(const eVector &z, Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>&, F_z_x)