16 #include <Eigen/LevenbergMarquardt> 18 using namespace Eigen;
20 template<
typename Scalar>
30 VectorType
model(
const VectorType& uv, VectorType&
x)
34 int n = Base::inputs();
42 for (
int j = 0;
j <
m;
j++)
44 for (
int i = 0;
i < half;
i++)
53 m_y = this->
model(uv_ref, x);
60 int n = Base::inputs();
67 for (
int j = 0;
j <
m;
j++)
70 for (
int i = 0;
i < half;
i++)
78 int df(
const VectorType& uv, JacobianType& fjac)
81 int n = Base::inputs();
88 for (
int j = 0;
j <
m;
j++)
90 for (
int i = 0;
i < half;
i++)
101 template<
typename FunctorType,
typename VectorType>
114 template<
typename FunctorType,
typename VectorType>
127 template<
typename FunctorType,
typename VectorType>
153 VectorType uv(inputs),uv_ref(inputs);
154 VectorType
x(values);
157 uv_ref << -2, 1, 4 ,8, 6, 1.8, 1.2, 1.1, 1.9 , 3;
172 u.setOnes(); v.setOnes();
176 u.setOnes(); v.setOnes();
180 v.setOnes(); u.setOnes();
LevenbergMarquardtSpace::Status minimize(FVectorType &x)
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
LevenbergMarquardtSpace::Status minimizeOneStep(FVectorType &x)
Performs non linear optimization over a non-linear function, using a variant of the Levenberg Marquar...
noiseModel::Diagonal::shared_ptr model
DenseFunctor< Scalar > Base
Namespace containing all symbols from the Eigen library.
void initPoints(VectorType &uv_ref, VectorType &x)
Matrix< Scalar, Dynamic, 1 > VectorType
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
int operator()(const VectorType &uv, VectorType &fvec)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
int test_lmder(FunctorType &functor, VectorType &uv)
Expression of a fixed-size or dynamic-size sub-vector.
#define VERIFY_IS_EQUAL(a, b)
Array< int, Dynamic, 1 > v
Base::JacobianType JacobianType
EIGEN_DECLARE_TEST(denseLM)
int df(const VectorType &uv, JacobianType &fjac)
LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x)
VectorType model(const VectorType &uv, VectorType &x)
#define CALL_SUBTEST_2(FUNC)
Jet< T, N > pow(const Jet< T, N > &f, double g)
LevenbergMarquardtSpace::Status lmder1(FVectorType &x, const Scalar tol=std::sqrt(NumTraits< Scalar >::epsilon()))
The matrix class, also used for vectors and row-vectors.
int test_minimizeSteps(FunctorType &functor, VectorType &uv)
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
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
int test_minimizeLM(FunctorType &functor, VectorType &uv)