10 #ifndef EIGEN_AUTODIFF_JACOBIAN_H 11 #define EIGEN_AUTODIFF_JACOBIAN_H 23 #if EIGEN_HAS_VARIADIC_TEMPLATES 24 template<
typename...
T>
29 template<
typename T0,
typename T1>
31 template<
typename T0,
typename T1,
typename T2>
53 #if EIGEN_HAS_VARIADIC_TEMPLATES 61 template<
typename... ParamsType>
62 void operator() (
const InputType&
x, ValueType*
v, JacobianType* _jac,
63 const ParamsType&...
Params)
const 65 void operator() (
const InputType& x, ValueType* v, JacobianType* _jac=0) const
72 #if EIGEN_HAS_VARIADIC_TEMPLATES 80 JacobianType& jac = *_jac;
82 ActiveInput ax = x.template cast<ActiveScalar>();
83 ActiveValue av(jac.
rows());
86 for (Index
j=0;
j<jac.
rows();
j++)
87 av[
j].derivatives().
resize(x.rows());
89 for (Index
i=0;
i<jac.
cols();
i++)
90 ax[
i].derivatives() = DerivativeType::Unit(x.rows(),
i);
92 #if EIGEN_HAS_VARIADIC_TEMPLATES 98 for (Index
i=0;
i<jac.
rows();
i++)
100 (*v)[
i] = av[
i].value();
101 jac.row(
i) = av[
i].derivatives();
108 #endif // EIGEN_AUTODIFF_JACOBIAN_H
AutoDiffJacobian(const T0 &a0)
#define EIGEN_STRONG_INLINE
void operator()(const InputType &x, ValueType *v, JacobianType *_jac=0) const
JacobianType::Index Index
Matrix< ActiveScalar, ValuesAtCompileTime, 1 > ActiveValue
A scalar type replacement with automatic differentiation capability.
AutoDiffJacobian(const Functor &f)
Namespace containing all symbols from the Eigen library.
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
Matrix< Scalar, InputsAtCompileTime, 1 > DerivativeType
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
Matrix< Scalar, InputsAtCompileTime, 1 > InputType
AutoDiffScalar< DerivativeType > ActiveScalar
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
Matrix< Scalar, ValuesAtCompileTime, 1 > ValueType
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Matrix< ActiveScalar, InputsAtCompileTime, 1 > ActiveInput
Array< int, Dynamic, 1 > v
Functor::InputType InputType
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
AutoDiffJacobian(const T0 &a0, const T1 &a1, const T2 &a2)
Functor::ValueType ValueType
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
AutoDiffJacobian(const T0 &a0, const T1 &a1)
static std::shared_ptr< PreintegratedCombinedMeasurements::Params > Params(const Matrix3 &biasAccCovariance=Matrix3::Zero(), const Matrix3 &biasOmegaCovariance=Matrix3::Zero(), const Matrix6 &biasAccOmegaInt=Matrix6::Zero())
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
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
Matrix< Scalar, ValuesAtCompileTime, InputsAtCompileTime > JacobianType