Go to the documentation of this file.
19 #ifndef EIGEN_LEVENBERGMARQUARDT_H
20 #define EIGEN_LEVENBERGMARQUARDT_H
24 namespace LevenbergMarquardtSpace {
41 template <
typename _Scalar,
int NX=Dynamic,
int NY=Dynamic>
68 template <
typename _Scalar,
typename _Index>
96 template <
typename QRSolver,
typename VectorType>
109 template<
typename _FunctorType>
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)
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
Namespace containing all symbols from the Eigen library.
FunctorType::JacobianType JacobianType
A versatible sparse matrix representation.
DenseFunctor(int inputs, int values)
JacobianType::Scalar Scalar
void setExternalScaling(bool value)
Matrix diag(const std::vector< Matrix > &Hs)
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
RealScalar factor() const
RealScalar epsilon() const
void lmpar2(const QRSolver &qr, const VectorType &diag, const VectorType &qtb, typename VectorType::Scalar m_delta, typename VectorType::Scalar &par, VectorType &x)
bool m_useExternalScaling
Performs non linear optimization over a non-linear function, using a variant of the Levenberg Marquar...
Matrix< Scalar, Dynamic, 1 > FVectorType
JacobianType & jacobian()
void setEpsilon(RealScalar epsfcn)
SparseFunctor(int inputs, int values)
Matrix< Scalar, ValuesAtCompileTime, 1 > ValueType
@ RelativeErrorAndReductionTooSmall
LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x)
JacobianType::RealScalar RealScalar
void setFtol(RealScalar ftol)
@ ImproperInputParameters
LevenbergMarquardtSpace::Status lmder1(FVectorType &x, const Scalar tol=std::sqrt(NumTraits< Scalar >::epsilon()))
Matrix< Scalar, ValuesAtCompileTime, InputsAtCompileTime > JacobianType
ComputationInfo info() const
Reports whether the minimization was successful.
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
static LevenbergMarquardtSpace::Status lmdif1(FunctorType &functor, FVectorType &x, Index *nfev, const Scalar tol=std::sqrt(NumTraits< Scalar >::epsilon()))
ColPivHouseholderQR< JacobianType > QRSolver
LevenbergMarquardtSpace::Status minimizeOneStep(FVectorType &x)
NumTraits< Scalar >::Real RealScalar
Matrix< Scalar, InputsAtCompileTime, 1 > InputType
void setGtol(RealScalar gtol)
HouseholderQR< MatrixXf > qr(A)
void setFactor(RealScalar factor)
PermutationMatrix< Dynamic, Dynamic, int > PermutationType
@ TooManyFunctionEvaluation
Matrix< Scalar, Dynamic, 1 > ValueType
@ RelativeReductionTooSmall
void setXtol(RealScalar xtol)
RealScalar lm_param(void)
PermutationType permutation()
The matrix class, also used for vectors and row-vectors.
PermutationType m_permutation
FunctorType::QRSolver QRSolver
LevenbergMarquardtSpace::Status minimize(FVectorType &x)
void setMaxfev(Index maxfev)
SparseMatrix< Scalar, ColMajor, Index > JacobianType
Sparse left-looking QR factorization with numerical column pivoting.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
SparseQR< JacobianType, COLAMDOrdering< int > > QRSolver
Jet< T, N > sqrt(const Jet< T, N > &f)
QRSolver::StorageIndex PermIndex
LevenbergMarquardt(FunctorType &functor)
Matrix< Scalar, Dynamic, 1 > InputType
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:33:06