11 #include <Eigen/Dense> 13 #define NUMBER_DIRECTIONS 16 14 #include <unsupported/Eigen/AdolcForward> 16 template<
typename Vector>
20 return (p-
Vector(
Scalar(-1),
Scalar(1.))).norm() + (p.array().sqrt().abs() * p.array().sin()).
sum() + p.dot(p);
23 template<
typename _Scalar,
int NX=Dynamic,
int NY=Dynamic>
48 v[0] = 2 * x[0] * x[0] + x[0] * x[1];
49 v[1] = 3 * x[1] * x[0] + 0.5 * x[1] * x[1];
57 v[2] = 3 * x[1] * x[0] * x[0];
63 void operator() (
const InputType&
x, ValueType*
v, JacobianType* _j)
const 69 JacobianType&
j = *_j;
71 j(0,0) = 4 * x[0] + x[1];
75 j(1,1) = 3 * x[0] + 2 * 0.5 * x[1];
84 j(2,0) = 3 * x[1] * 2 * x[0];
85 j(2,1) = 3 * x[0] * x[0];
92 j(2,2) = 3 * x[1] * x[0] * x[0];
93 j(2,2) = 3 * x[1] * x[0] * x[0];
101 typename Func::InputType
x = Func::InputType::Random(f.inputs());
102 typename Func::ValueType
y(f.values()), yref(f.values());
103 typename Func::JacobianType
j(f.values(),f.inputs()), jref(f.values(),f.inputs());
113 AdolcForwardJacobian<Func> autoj(f);
139 A.selfadjointView<
Lower>().eigenvalues();
Matrix< Scalar, ValuesAtCompileTime, 1 > ValueType
EIGEN_DONT_INLINE Vector::Scalar foo(const Vector &p)
void operator()(const Matrix< T, InputsAtCompileTime, 1 > &x, Matrix< T, ValuesAtCompileTime, 1 > *_v) const
TestFunc1(int inputs, int values)
void test_forward_adolc()
#define EIGEN_DONT_INLINE
#define VERIFY_IS_APPROX(a, b)
Matrix< Scalar, InputsAtCompileTime, 1 > InputType
Matrix< Scalar, ValuesAtCompileTime, InputsAtCompileTime > JacobianType
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
const mpreal sum(const mpreal tab[], const unsigned long int n, int &status, mp_rnd_t mode=mpreal::get_default_rnd())
void adolc_forward_jacobian(const Func &f)
#define CALL_SUBTEST(FUNC)
#define NUMBER_DIRECTIONS
The matrix class, also used for vectors and row-vectors.
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::Matrix< double, Eigen::Dynamic, 1 > Vector