Non-linear optimization routines. There are three methods implemented that include Gauss-Newton, Levenberg-Marquardt and Tukey m-estimator.
More...
#include <Optimization.h>
|
void | CalcJacobian (CvMat *x, CvMat *J, EstimateCallback Estimate) |
| Numerically differentiates and calculates the Jacobian around x. More...
|
|
CvMat * | GetErr () |
| Returns the current residual vector. More...
|
|
| Optimization (int n_params, int n_meas) |
| Constructor. More...
|
|
double | Optimize (CvMat *parameters, CvMat *measurements, double stop, int max_iter, EstimateCallback Estimate, void *param=0, OptimizeMethod method=LEVENBERGMARQUARDT, CvMat *parameters_mask=0, CvMat *J_mat=0, CvMat *weights=0) |
| Runs the optimization loop with selected parameters. More...
|
|
| ~Optimization () |
|
Non-linear optimization routines. There are three methods implemented that include Gauss-Newton, Levenberg-Marquardt and Tukey m-estimator.
- Examples:
- SampleOptimization.cpp.
Definition at line 44 of file Optimization.h.
typedef void(* alvar::Optimization::EstimateCallback) (CvMat *state, CvMat *projection, void *param) |
Pointer to the function that projects the state of the system to the measurements.
- Parameters
-
state | System parameters, e.g. camera parameterization in optical tracking. |
projection | The system state projection is stored here. E.g image measurements in optical tracking. |
param | Additional parameters to the function. E.g. some constant parameters that are not optimized. |
Definition at line 101 of file Optimization.h.
Selection between the algorithm used in optimization. Following should be noticed:
Enumerator |
---|
GAUSSNEWTON |
|
LEVENBERGMARQUARDT |
|
TUKEY_LM |
|
Definition at line 74 of file Optimization.h.
alvar::Optimization::Optimization |
( |
int |
n_params, |
|
|
int |
n_meas |
|
) |
| |
Constructor.
- Parameters
-
n_params | Number of parameters to be optimized. |
n_meas | Number of measurements that are observed. |
Definition at line 34 of file Optimization.cpp.
alvar::Optimization::~Optimization |
( |
| ) |
|
void alvar::Optimization::CalcJacobian |
( |
CvMat * |
x, |
|
|
CvMat * |
J, |
|
|
EstimateCallback |
Estimate |
|
) |
| |
Numerically differentiates and calculates the Jacobian around x.
- Parameters
-
x | The set of parameters around which the Jacobian is evaluated. |
J | Resulting Jacobian matrix is stored here. |
Estimate | The function to be differentiated. |
Definition at line 99 of file Optimization.cpp.
double alvar::Optimization::CalcTukeyWeight |
( |
double |
residual, |
|
|
double |
c |
|
) |
| |
|
private |
double alvar::Optimization::CalcTukeyWeightSimple |
( |
double |
residual, |
|
|
double |
c |
|
) |
| |
|
private |
CvMat* alvar::Optimization::GetErr |
( |
| ) |
|
|
inline |
Returns the current residual vector.
- Returns
- Pointer to the residual vector.
Definition at line 93 of file Optimization.h.
double alvar::Optimization::Optimize |
( |
CvMat * |
parameters, |
|
|
CvMat * |
measurements, |
|
|
double |
stop, |
|
|
int |
max_iter, |
|
|
EstimateCallback |
Estimate, |
|
|
void * |
param = 0 , |
|
|
OptimizeMethod |
method = LEVENBERGMARQUARDT , |
|
|
CvMat * |
parameters_mask = 0 , |
|
|
CvMat * |
J_mat = 0 , |
|
|
CvMat * |
weights = 0 |
|
) |
| |
Runs the optimization loop with selected parameters.
- Parameters
-
parameters | Vector of parameters to be optimized. Initial values should be set. |
measurements | Vector of measurements that are observed. |
stop | Optimization loop ends as the stop limit is reached. Criteria is calculated as |
max_iter | Maximum number of iteration loops that are evaluated if stop is not reached. |
Estimate | Pointer to the function that maps the state to the measurements. See EstimateCallback. |
method | One of the three possible optimization methods. |
parameters_mask | Vector that defines the parameters that are optimized. If vector element is 0, corresponding parameter is not altered. |
J_mat | Jacobian matrix. If not given, numerical differentation is used. |
weights | Weight vector that can be submitted to give different weights to different measurements. Currently works only with OptimizeMethod::TUKEY_LM. |
- Examples:
- SampleOptimization.cpp.
Definition at line 123 of file Optimization.cpp.
CvMat* alvar::Optimization::delta |
|
private |
CvMat* alvar::Optimization::diag |
|
private |
CvMat* alvar::Optimization::err |
|
private |
void* alvar::Optimization::estimate_param |
|
private |
CvMat* alvar::Optimization::J |
|
private |
CvMat* alvar::Optimization::JtJ |
|
private |
double alvar::Optimization::lambda |
|
private |
CvMat* alvar::Optimization::tmp |
|
private |
CvMat* alvar::Optimization::tmp_par |
|
private |
CvMat* alvar::Optimization::W |
|
private |
CvMat* alvar::Optimization::x_minus |
|
private |
CvMat* alvar::Optimization::x_plus |
|
private |
CvMat* alvar::Optimization::x_tmp1 |
|
private |
CvMat* alvar::Optimization::x_tmp2 |
|
private |
The documentation for this class was generated from the following files: