Using custom scalar types

By default, Eigen currently supports standard floating-point types (float, double, std::complex<float>, std::complex<double>, long double), as well as all native integer types (e.g., int, unsigned int, short, etc.), and bool. On x86-64 systems, long double permits to locally enforces the use of x87 registers with extended accuracy (in comparison to SSE).

In order to add support for a custom type T you need:

  1. make sure the common operator (+,-,*,/,etc.) are supported by the type T
  2. add a specialization of struct Eigen::NumTraits<T> (see NumTraits)
  3. define the math functions that makes sense for your type. This includes standard ones like sqrt, pow, sin, tan, conj, real, imag, etc, as well as abs2 which is Eigen specific. (see the file Eigen/src/Core/MathFunctions.h)

The math function should be defined in the same namespace than T, or in the std namespace though that second approach is not recommended.

Here is a concrete example adding support for the Adolc's adouble type. Adolc is an automatic differentiation library. The type adouble is basically a real value tracking the values of any number of partial derivatives.

#ifndef ADOLCSUPPORT_H
#define ADOLCSUPPORT_H
#define ADOLC_TAPELESS
#include <adolc/adouble.h>
#include <Eigen/Core>
namespace Eigen {
template<> struct NumTraits<adtl::adouble>
: NumTraits<double> // permits to get the epsilon, dummy_precision, lowest, highest functions
{
typedef adtl::adouble Real;
typedef adtl::adouble NonInteger;
typedef adtl::adouble Nested;
enum {
IsComplex = 0,
IsInteger = 0,
IsSigned = 1,
ReadCost = 1,
AddCost = 3,
MulCost = 3
};
};
}
namespace adtl {
inline const adouble& conj(const adouble& x) { return x; }
inline const adouble& real(const adouble& x) { return x; }
inline adouble imag(const adouble&) { return 0.; }
inline adouble abs(const adouble& x) { return fabs(x); }
inline adouble abs2(const adouble& x) { return x*x; }
}
#endif // ADOLCSUPPORT_H

This other example adds support for the mpq_class type from GMP. It shows in particular how to change the way Eigen picks the best pivot during LU factorization. It selects the coefficient with the highest score, where the score is by default the absolute value of a number, but we can define a different score, for instance to prefer pivots with a more compact representation (this is an example, not a recommendation). Note that the scores should always be non-negative and only zero is allowed to have a score of zero. Also, this can interact badly with thresholds for inexact scalar types.

#include <gmpxx.h>
#include <Eigen/Core>
#include <boost/operators.hpp>
namespace Eigen {
template<> struct NumTraits<mpq_class> : GenericNumTraits<mpq_class>
{
typedef mpq_class Real;
typedef mpq_class NonInteger;
typedef mpq_class Nested;
static inline Real epsilon() { return 0; }
static inline Real dummy_precision() { return 0; }
static inline int digits10() { return 0; }
enum {
IsInteger = 0,
IsSigned = 1,
IsComplex = 0,
ReadCost = 6,
AddCost = 150,
MulCost = 100
};
};
namespace internal {
template<> struct scalar_score_coeff_op<mpq_class> {
struct result_type : boost::totally_ordered1<result_type> {
result_type(int i = 0) : len(i) {} // Eigen uses Score(0) and Score()
result_type(mpq_class const& q) :
len(mpz_size(q.get_num_mpz_t())+
mpz_size(q.get_den_mpz_t())-1) {}
// 0 is the worst possible pivot
if (x.len == 0) return y.len > 0;
if (y.len == 0) return false;
// Prefer a pivot with a small representation
return x.len > y.len;
}
// Only used to test if the score is 0
return x.len == y.len;
}
};
result_type operator()(mpq_class const& x) const { return x; }
};
}
}
Eigen::internal::operator==
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool operator==(const TensorUInt128< HL, LL > &lhs, const TensorUInt128< HR, LR > &rhs)
Definition: TensorUInt128.h:79
Eigen::conj
const AutoDiffScalar< DerType > & conj(const AutoDiffScalar< DerType > &x)
Definition: AutoDiffScalar.h:574
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
Eigen::internal::scalar_abs_op::operator()
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE result_type operator()(const Scalar &a) const
Definition: UnaryFunctors.h:44
x
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
Definition: gnuplot_common_settings.hh:12
Eigen::GenericNumTraits::IsSigned
@ IsSigned
Definition: NumTraits.h:156
abs2
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Abs2ReturnType abs2() const
Definition: ArrayCwiseUnaryOps.h:80
boost::multiprecision::fabs
Real fabs(const Real &a)
Definition: boostmultiprec.cpp:119
epsilon
static double epsilon
Definition: testRot3.cpp:37
Eigen::GenericNumTraits::MulCost
@ MulCost
Definition: NumTraits.h:161
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
Eigen::GenericNumTraits::ReadCost
@ ReadCost
Definition: NumTraits.h:159
Eigen::internal::operator<
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool operator<(const TensorUInt128< HL, LL > &lhs, const TensorUInt128< HR, LR > &rhs)
Definition: TensorUInt128.h:103
size_t
std::size_t size_t
Definition: wrap/pybind11/include/pybind11/detail/common.h:476
Eigen::GenericNumTraits::IsInteger
@ IsInteger
Definition: NumTraits.h:155
Eigen::GenericNumTraits::RequireInitialization
@ RequireInitialization
Definition: NumTraits.h:158
Eigen::real
const AutoDiffScalar< DerType > & real(const AutoDiffScalar< DerType > &x)
Definition: AutoDiffScalar.h:576
Eigen::imag
DerType::Scalar imag(const AutoDiffScalar< DerType > &)
Definition: AutoDiffScalar.h:578
Eigen::GenericNumTraits::AddCost
@ AddCost
Definition: NumTraits.h:160
Eigen::internal::y
const Scalar & y
Definition: Eigen/src/Core/MathFunctions.h:821
Real
mp::number< mp::cpp_dec_float< 100 >, mp::et_on > Real
Definition: boostmultiprec.cpp:78
abs
#define abs(x)
Definition: datatypes.h:17
len
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2399
internal
Definition: BandTriangularSolver.h:13
Eigen::GenericNumTraits::IsComplex
@ IsComplex
Definition: NumTraits.h:157
Eigen::internal::scalar_abs_op::result_type
NumTraits< Scalar >::Real result_type
Definition: UnaryFunctors.h:43
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Eigen::GenericNumTraits::Real
T Real
Definition: NumTraits.h:164


gtsam
Author(s):
autogenerated on Wed May 15 2024 15:27:19