19 #ifndef EIGEN_LEVENBERGMARQUARDT_H 20 #define EIGEN_LEVENBERGMARQUARDT_H 24 namespace LevenbergMarquardtSpace {
41 template <
typename _Scalar,
int NX=Dynamic,
int NY=Dynamic>
46 InputsAtCompileTime = NX,
47 ValuesAtCompileTime = NY
55 DenseFunctor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}
56 DenseFunctor(
int inputs,
int values) : m_inputs(inputs), m_values(values) {}
58 int inputs()
const {
return m_inputs; }
59 int values()
const {
return m_values; }
68 template <
typename _Scalar,
typename _Index>
82 SparseFunctor(
int inputs,
int values) : m_inputs(inputs), m_values(values) {}
84 int inputs()
const {
return m_inputs; }
85 int values()
const {
return m_values; }
96 template <
typename QRSolver,
typename VectorType>
98 typename VectorType::Scalar m_delta,
typename VectorType::Scalar &par,
109 template<
typename _FunctorType>
116 typedef typename JacobianType::Scalar
Scalar;
123 : m_functor(functor),m_nfev(0),m_njev(0),m_fnorm(0.0),m_gnorm(0),
127 m_useExternalScaling=
false;
138 FunctorType &functor,
158 void setXtol(RealScalar xtol) { m_xtol = xtol; }
161 void setFtol(RealScalar ftol) { m_ftol = ftol; }
164 void setGtol(RealScalar gtol) { m_gtol = gtol; }
167 void setFactor(RealScalar factor) { m_factor = factor; }
179 RealScalar
xtol()
const {
return m_xtol; }
182 RealScalar
ftol()
const {
return m_ftol; }
185 RealScalar
gtol()
const {
return m_gtol; }
188 RealScalar
factor()
const {
return m_factor; }
191 RealScalar
epsilon()
const {
return m_epsfcn; }
197 FVectorType&
diag() {
return m_diag; }
209 RealScalar
fnorm() {
return m_fnorm; }
212 RealScalar
gnorm() {
return m_gnorm; }
219 FVectorType&
fvec() {
return m_fvec; }
269 FVectorType m_wa1, m_wa2, m_wa3,
m_wa4;
275 template<
typename FunctorType>
281 m_isInitialized =
true;
286 status = minimizeOneStep(x);
288 m_isInitialized =
true;
292 template<
typename FunctorType>
297 m = m_functor.values();
299 m_wa1.
resize(n); m_wa2.resize(n); m_wa3.resize(n);
305 if (!m_useExternalScaling)
307 eigen_assert( (!m_useExternalScaling || m_diag.size()==n) &&
"When m_useExternalScaling is set, the caller must provide a valid 'm_diag'");
315 if (n <= 0 || m < n || m_ftol < 0. || m_xtol < 0. || m_gtol < 0. || m_maxfev <= 0 || m_factor <= 0.){
320 if (m_useExternalScaling)
321 for (
Index j = 0; j < n; ++j)
331 if ( m_functor(x, m_fvec) < 0)
333 m_fnorm = m_fvec.stableNorm();
342 template<
typename FunctorType>
350 m = m_functor.values();
353 if (n <= 0 || m < n || tol < 0.)
359 m_maxfev = 100*(n+1);
365 template<
typename FunctorType>
375 Index m = functor.values();
378 if (n <= 0 || m < n || tol < 0.)
396 #endif // EIGEN_LEVENBERGMARQUARDT_H
LevenbergMarquardtSpace::Status minimize(FVectorType &x)
JacobianType::RealScalar RealScalar
Matrix< Scalar, ValuesAtCompileTime, InputsAtCompileTime > JacobianType
static LevenbergMarquardtSpace::Status lmdif1(FunctorType &functor, FVectorType &x, Index *nfev, const Scalar tol=std::sqrt(NumTraits< Scalar >::epsilon()))
Matrix< Scalar, Dynamic, 1 > FVectorType
A versatible sparse matrix representation.
Performs non linear optimization over a non-linear function, using a variant of the Levenberg Marquar...
JacobianType & jacobian()
Matrix< Scalar, ValuesAtCompileTime, 1 > ValueType
void lmpar2(const QRSolver &qr, const VectorType &diag, const VectorType &qtb, typename VectorType::Scalar m_delta, typename VectorType::Scalar &par, VectorType &x)
JacobianType::Scalar Scalar
SparseQR< JacobianType, COLAMDOrdering< int > > QRSolver
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
ColPivHouseholderQR< JacobianType > QRSolver
Matrix< Scalar, InputsAtCompileTime, 1 > InputType
RealScalar epsilon() const
PermutationType permutation()
Matrix< Scalar, Dynamic, 1 > ValueType
void setFtol(RealScalar ftol)
Sparse left-looking rank-revealing QR factorization.
void setEpsilon(RealScalar epsfcn)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
bool m_useExternalScaling
void setMaxfev(Index maxfev)
SparseMatrix< Scalar, ColMajor, Index > JacobianType
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
PermutationType m_permutation
RealScalar lm_param(void)
Matrix< Scalar, Dynamic, 1 > InputType
ComputationInfo info() const
Reports whether the minimization was successful.
LevenbergMarquardt(FunctorType &functor)
DenseFunctor(int inputs, int values)
RealScalar factor() const
FunctorType::QRSolver QRSolver
FunctorType::JacobianType JacobianType
void setFactor(RealScalar factor)
QRSolver::StorageIndex PermIndex
void setXtol(RealScalar xtol)
LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x)
SparseFunctor(int inputs, int values)
LevenbergMarquardtSpace::Status lmder1(FVectorType &x, const Scalar tol=std::sqrt(NumTraits< Scalar >::epsilon()))
PermutationMatrix< Dynamic, Dynamic > PermutationType
The matrix class, also used for vectors and row-vectors.
void setGtol(RealScalar gtol)
void setExternalScaling(bool value)