Cookbook/Common issues

Eigen mostly achieves a pleasantly readable mathematical syntax, but quirks of the C++ language sometimes show through. This section lists some common gotchas you may encounter when using Eigen.

Structures containing Eigen types as members

Suppose you are using a fixed-size vectorizable Eigen type in one of your own structures, which you allocate dynamically:

   1 class Foo
   2 {
   3   double x;
   4   Eigen::Vector2d v;
   5 }
   6 
   7 Foo foo;                // Fine
   8 Foo *foo_ptr = new Foo; // PROBLEM!
   9 

Eigen ensures that Eigen::Vector2d v is 128-bit aligned with respect to the start of Foo. Stack-allocating an instance of Foo will also respect the alignment. The problem comes when dynamically allocating an instance of Foo; the default operator new is not required to allocate a 128-bit aligned block of data, so member foo_ptr->v may be misaligned.

To address this, Eigen provides a macro which overloads Foo's operator new to Do The Right Thing:

   1 class Foo
   2 {
   3   double x;
   4   Eigen::Vector2d v;
   5 public:
   6   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
   7 }
   8 
   9 Foo foo;                // Still fine
  10 Foo *foo_ptr = new Foo; // Now OK!
  11 

Full explanation: http://eigen.tuxfamily.org/dox/StructHavingEigenMembers.html

Using Eigen types with STL containers

When using fixed-size vectorizable Eigen types in STL containers, you must use an aligned allocator. Eigen provides one:

   1 USING_PART_OF_NAMESPACE_EIGEN
   2 
   3 // Instead of
   4 std::map<int, Vector4f> m; // WRONG
   5 // Use
   6 std::map<int, Vector4f, std::less<int>, Eigen::aligned_allocator<Vector4f> > m;

Unfortunately the situation with std::vector is complicated by a defect in the current C++ language definition; Eigen provides a header specifically to make std::vector work with aligned types:

   1 #define EIGEN_USE_NEW_STDVECTOR
   2 #include <Eigen/StdVector>
   3 
   4 std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > v;

The macro EIGEN_USE_NEW_STDVECTOR will avoid some problems with the original version of Eigen/StdVector and make your code forward-compatible with future versions of Eigen.

Full explanation: http://eigen.tuxfamily.org/dox/StlContainers.html

Syntax for calling member templates

Eigen's matrix types are class templates, allowing you to configure them on element type, storage order (e.g. row-major or col-major), or specify fixed sizes for one or both dimensions. Some member functions of these matrix types have template parameters of their own which the user must specify explicitly; these are member templates.

   1 template<typename T>
   2 class Foo
   3 {
   4   void bar();                 // Normal member function
   5   template<int N> void baz(); // Member template
   6 };

For example, Eigen's MatrixBase (inherited by Matrix) has a useful member template block, which returns a read-write view of a sub-block of a matrix:

   1 template<int BlockRows, int BlockCols>
   2 ReturnType block(int startRow, int startCol);

If we know the dimensions of the block at compile time, specifying them as template parameters is a nice win; it avoids unnecessary dynamic memory allocations, and may allow Eigen to perform optimizations such as vectorization and loop unrolling. Unfortunately, calling a member template can be tricky:

   1 // This works:
   2 void transform(Eigen::Matrix<double,3,4>& m,
   3                const Eigen::Matrix<double,3,3> trans,
   4                const Eigen::Quaternion<double> qrot)
   5 {
   6   m.block<3,3>(0,0) = qrot.toRotationMatrix().transpose();
   7   m.block<3,1>(0,3) = -m.block<3,3>(0,0) * trans;
   8 }
   9 
  10 // But when we template on the element type, this fails to compile!
  11 template<typename T>
  12 void transform(Eigen::Matrix<T,3,4>& m,
  13                const Eigen::Matrix<T,3,3> trans,
  14                const Eigen::Quaternion<T> qrot)
  15 {
  16   m.block<3,3>(0,0) = qrot.toRotationMatrix().transpose();
  17   m.block<3,1>(0,3) = -m.block<3,3>(0,0) * trans;
  18 }

In the second (templated) case, not only will it (correctly) fail to compile, gcc will misparse the expression so thoroughly that you get error messages along the lines of "warning: left-hand operand of comma has no effect", "error: lvalue required as left operand of assignment", "error: invalid operands of types '<unresolved overloaded function type>' and 'int' to binary 'operator<'".

What happened? In the second case, the matrix types are dependent on the template parameter T. Dependent types require us to give the compiler a little extra help. We need to preface the name of the member template with the keyword template:

   1 // Correct!
   2 template<typename T>
   3 void transform(Eigen::Matrix<T,3,4>& m,
   4                const Eigen::Matrix<T,3,3> trans,
   5                const Eigen::Quaternion<T> qrot)
   6 {
   7   m.template block<3,3>(0,0) = qrot.toRotationMatrix().transpose();
   8   m.template block<3,1>(0,3) = -m.template block<3,3>(0,0) * trans;
   9 }

Using other Eigen functions, below is another (perhaps cleaner) way to write the function body. Note that col is not a member template.

   1 m.template corner<3,3>(Eigen::TopLeft) = qrot.toRotationMatrix().transpose();
   2 m.col(3) = -m.template corner<3,3>(Eigen::TopLeft) * trans;

Member functions of Eigen::MatrixBase which are member templates include block, cast, corner, end, lpNorm, part, segment, and start. Many of these functions have overloads which are not member templates; those replace the template arguments with regular function arguments, which is more flexible but introduces runtime overhead.

Creating typedefs for Eigen types

Creating a typedef for a fully-defined Eigen type is easy:

   1 typedef Eigen::Matrix<float,3,1> Point;
   2 
   3 Point pt;

But what if we want to parameterize our Point type over floats and doubles? Then we want something like:

   1 // NOT LEGAL C++!
   2 template<typename T>
   3 typedef Eigen::Matrix<T,3,1> Point;
   4 
   5 Point<float> pt;

Unfortunately C++ does not currently allow template typedefs (they will be in C++0x with different syntax). The standard workaround is to make Point a "meta-function" that returns the desired type through its member typedef type:

   1 template<typename T>
   2 struct Point
   3 {
   4   typedef Eigen::Matrix<T,3,1> type;
   5 };
   6 
   7 Point<float>::type pt;

This approach is still fairly simple, but introduces a bit of syntactic noise since the user has to remember to add ::type. Another approach is to use inheritance:

   1 // WARNING: Has some unexpected behavior, see below
   2 template<typename T>
   3 class Point : public Eigen::Matrix<T,3,1> {};
   4 
   5 Point<float> pt;

This looks like what we want; unfortunately the derived class Point does not inherit the constructors or assignment operators of the base Eigen type, so Point will not inter-operate nicely with regular Eigen matrices. Here is a more complex definition of Point that fixes those issues:

   1 template<typename T>
   2 class Point : public Eigen::Matrix<T,3,1>
   3 {
   4   typedef Eigen::Matrix<T,3,1> BaseClass;
   5 
   6 public:
   7   // 3-element constructor, delegates to base class constructor
   8   Point(const T& x, const T& y, const T& z)
   9     : BaseClass(x, y, z)
  10   {}
  11 
  12   // Copy constructor from any Eigen matrix type
  13   template<typename OtherDerived>
  14   Point(const Eigen::MatrixBase<OtherDerived>& other)
  15     : BaseClass(other)
  16   {}
  17 
  18   // Reuse assignment operators from base class
  19   using BaseClass::operator=;
  20 };
  21 
  22 // Now all of these operations work
  23 Point<float> pt(1.0, 2.5, -3.1);
  24 Eigen::Vector3f v = pt;
  25 pt = v;
  26 Point<float> pt2(v);

Wiki: eigen/Cookbook (last edited 2011-07-14 18:58:05 by ethanrublee)