15 #include <Eigen/LevenbergMarquardt> 18 using namespace Eigen;
20 template <
typename Scalar>
29 VectorType
model(
const VectorType& uv, VectorType&
x)
33 int n = Base::inputs();
42 for (
int j = 0;
j <
m;
j++)
44 for (
int i = 0;
i < half;
i++)
46 coeff = (
x(
j)-
i)/
v(
i);
48 if (coeff < 1. && coeff > 0.)
57 m_y = this->
model(uv_ref,x);
62 int n = Base::inputs();
70 for (
int j = 0;
j <
m;
j++)
72 for (
int i = 0;
i < half;
i++)
74 coeff = (m_x(
j)-
i)/
v(
i);
76 if (coeff < 1. && coeff > 0.)
83 int df(
const VectorType& uv, JacobianType& fjac)
86 int n = Base::inputs();
102 if(coeff < 1. && coeff > 0.)
115 if(coeff < 1. && coeff > 0.)
136 VectorType uv(inputs),uv_ref(inputs);
137 VectorType
x(values);
139 uv_ref << -2, 1, 4 ,8, 6, 1.8, 1.2, 1.1, 1.9 , 3;
163 MatrixXd Err(values, maxiter);
164 MatrixXd Mod(values, maxiter);
173 CALL_SUBTEST_1(test_sparseLM_T<double>());
SparseFunctor< Scalar, int > Base
Matrix< Scalar, Dynamic, 1 > VectorType
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
sparseGaussianTest(int inputs, int values)
A versatible sparse matrix representation.
Performs non linear optimization over a non-linear function, using a variant of the Levenberg Marquar...
noiseModel::Diagonal::shared_ptr model
Namespace containing all symbols from the Eigen library.
void initPoints(VectorType &uv_ref, VectorType &x)
iterator iter(handle obj)
int operator()(const VectorType &uv, VectorType &fvec)
Expression of a fixed-size or dynamic-size sub-vector.
#define VERIFY_IS_EQUAL(a, b)
int df(const VectorType &uv, JacobianType &fjac)
Scalar & coeffRef(Index row, Index col)
LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x)
Jet< T, N > pow(const Jet< T, N > &f, double g)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Base::JacobianType JacobianType
VectorType model(const VectorType &uv, VectorType &x)