C++ Eigen
- Description: Eigen linear algebra — matrices, storage order, decompositions and solvers, geometry (rotations/quaternions/axis-angle for SLAM,
wxyzvsxyzw, homogeneous coords), aliasing and theauto-with-expression-templates pitfall - My Notion Note ID: K2A-B2-5
- Created: 2020-01-17
- Updated: 2026-04-30
- License: Reuse is very welcome. Please credit Yu Zhang and link back to the original on yuzhang.io
Table of Contents
- 1. What Eigen Is
- 2. Matrix and Vector Types
- 3. Construction and Access
- 4. Arithmetic and Common Operations
- 5. Storage Order: Row-Major vs Column-Major
- 6. Solving Linear Systems and Decompositions
- 7. The Geometry Module
- 8. Aliasing and
.eval() - 9. The
autoPitfall with Expression Templates - 10. References
1. What Eigen Is
Eigen is a header-only C++ template library for linear algebra. It supports dense and sparse matrices and vectors, basic linear algebra operations, decompositions, and geometric primitives. Internally it uses expression templates: the result of A + B * C isn't a temporary matrix but a tree of objects that the compiler evaluates lazily, fusing operations and avoiding intermediate allocations.
Practical consequences:
- One include and you're done — no library to link.
- The compiler generates aggressively optimized code per call site, vectorizing where possible. To get the SIMD wins, build with
-O2(or-O3) and a vector ISA target like-march=native/-mavx2/-mfma. - Error messages are long and template-heavy.
- Mistakes around the lazy-evaluation model (
auto, aliasing, dangling references) bite in subtle ways. § 8 and § 9 cover the common ones.
If your code already parallelises at a higher level (TBB, OpenMP, your own thread pool), pass -DEIGEN_DONT_PARALLELIZE so Eigen doesn't internally use OpenMP and oversubscribe cores.
2. Matrix and Vector Types
The fundamental template is Matrix<Scalar, Rows, Cols>. Common typedefs:
| Type | Equivalent |
|---|---|
Vector3d |
Matrix<double, 3, 1> |
Vector3f |
Matrix<float, 3, 1> |
RowVector3d |
Matrix<double, 1, 3> |
Matrix3d |
Matrix<double, 3, 3> |
Matrix4f |
Matrix<float, 4, 4> |
MatrixXd |
Matrix<double, Dynamic, Dynamic> |
VectorXd |
Matrix<double, Dynamic, 1> |
Matrix<double, 3, Dynamic> |
3 rows, runtime cols |
Fixed-size types (Matrix3d, Vector4f) live on the stack and are a major source of Eigen's speed — the compiler unrolls everything. Dynamic-size types (MatrixXd) heap-allocate their storage.
Pick fixed when you can. A Vector3d is several times faster to construct, copy, and operate on than a VectorXd of length 3. Use dynamic only when the size is genuinely unknown at compile time.
Alignment. SIMD-friendly fixed-size types (Vector4d, Vector2d, Matrix4f, ...) require 16- or 32-byte alignment. If you store them inside your own classes, the class needs EIGEN_MAKE_ALIGNED_OPERATOR_NEW (pre-C++17) or you need a sufficiently recent compiler with C++17's over-aligned new (GCC ≥ 7, clang ≥ 5, MSVC ≥ 19.12). For containers, use std::vector<Vector4d, Eigen::aligned_allocator<Vector4d>> on older toolchains; modern C++17 compilers handle plain std::vector<Vector4d> correctly.
3. Construction and Access
#include <Eigen/Dense>
using namespace Eigen;
Vector3d v(1, 2, 3);
Matrix3d M;
M << 1, 2, 3,
4, 5, 6,
7, 8, 9;
MatrixXd A(3, 4); // uninitialized
A.setZero();
A.setIdentity(); // for square: identity; otherwise diag of 1s
A.setRandom();
A.setConstant(7.0);
double x = M(0, 1); // 2.0 -- (row, col)
v(2) = 30.0; // mutate
// Block access
M.row(0); // first row as a 1x3 expression
M.col(1); // second col as a 3x1 expression
M.block<2, 2>(0, 0); // top-left 2x2 (compile-time size)
M.block(0, 0, 2, 2); // top-left 2x2 (runtime size)
M.topLeftCorner(2, 2);
v.head<2>(); // first 2 elements
v.tail(2);
v.segment(1, 2); // 2 elements starting at index 1
Indexing is (row, col), always, regardless of storage order.
4. Arithmetic and Common Operations
Matrix3d A, B;
Vector3d u, v;
Matrix3d C = A + B;
Matrix3d D = A * B; // matrix product
Vector3d w = A * u; // matrix-vector product
double dot = u.dot(v);
Vector3d cross = u.cross(v); // only for size-3 vectors
double n = v.norm();
double n2 = v.squaredNorm();
Vector3d hat = v.normalized();
v.normalize(); // in place
// Component-wise (use .array())
Matrix3d E = A.array() * B.array(); // Hadamard product
Matrix3d F = A.array().square();
Matrix3d G = (A.array() > 0).select(A, -A); // |A|
// Reductions
double s = A.sum();
double mn = A.minCoeff();
double mx = A.maxCoeff();
double tr = A.trace();
double det = A.determinant();
Matrix3d In = A.inverse(); // small fixed-size only; use a solver otherwise
// Transpose / adjoint
Matrix3d At = A.transpose();
A.transposeInPlace(); // ok
A = A.transpose(); // BUG -- aliasing; see § 8
The .array() view turns a matrix into a coefficient-wise context (so * is element-wise, + is unchanged, scalar functions work). The .matrix() view turns it back. They're zero-cost.
5. Storage Order: Row-Major vs Column-Major
Eigen stores matrices in column-major order by default. Override per type:
Matrix<double, 3, 3, RowMajor> Mrow;
Matrix<double, 3, 3, ColMajor> Mcol; // explicit form of the default
typedef Matrix<float, Dynamic, Dynamic, RowMajor> RowMatrixXf;
Indexing, transposes, decompositions — all behave identically regardless of storage order. The difference matters in three places:
- Interop with external memory. When you wrap a raw pointer with
Eigen::Map, the layout in memory must match the declared storage order. Most numpy buffers, OpenCVMats, and image data are row-major. UseMap<MatrixXd, 0, Stride<Outer, Inner>>for arbitrary strides. - Performance of slicing.
M.row(i)is cheap on a row-major matrix and crosses strides on a column-major one (and vice versa forM.col(j)). Pick the layout that matches your access pattern. - Vector typedefs. Eigen's
VectorXdis column-major (a column vector).RowVectorXdis row-major (a row vector). They are not interchangeable in expressions that care about shape.
// Wrap an existing row-major buffer (e.g., from a Python/C library)
double buf[12];
Map<Matrix<double, 3, 4, RowMajor>> M(buf);
M(1, 2) = 5.0; // writes through to buf
6. Solving Linear Systems and Decompositions
Don't compute A.inverse() * b to solve A x = b. Use a decomposition:
| Decomposition | Matrix shape and properties | Use when |
|---|---|---|
PartialPivLU |
Square, invertible | General fast solve, stable enough |
FullPivLU |
Square | More stable, also gives rank/null space |
HouseholderQR |
Any | Least-squares, fast |
ColPivHouseholderQR |
Any | Least-squares, more stable, gives rank |
LLT (Cholesky) |
Square, symmetric positive-definite | Fast SPD solver |
LDLT |
Square, symmetric (positive or negative semidefinite) | Symmetric semidefinite — handles PSD/NSD cases that strict-PD LLT rejects, no sqrt |
JacobiSVD |
Any | Most stable, computes full SVD |
BDCSVD |
Any (large) | Faster SVD for large matrices |
MatrixXd A = MatrixXd::Random(3, 3);
VectorXd b = VectorXd::Random(3);
VectorXd x = A.colPivHouseholderQr().solve(b);
double residual = (A * x - b).norm();
// SPD case
MatrixXd K = A.transpose() * A; // SPD
VectorXd y = K.llt().solve(A.transpose() * b);
// Eigenvalues (self-adjoint case is much faster)
SelfAdjointEigenSolver<Matrix3d> es(K);
Vector3d evals = es.eigenvalues();
Matrix3d evecs = es.eigenvectors();
// SVD
JacobiSVD<MatrixXd> svd(A, ComputeThinU | ComputeThinV);
For small fixed-size matrices, A.inverse() is acceptable (it special-cases sizes ≤ 4). For anything bigger or runtime-sized, use a solver — A.inverse() * b is both slower (forms the full inverse) and less numerically stable than solver.solve(b).
7. The Geometry Module
#include <Eigen/Geometry> adds rotation, translation, and rigid-transform types tailored for 3D work — the bread-and-butter of SLAM, robotics, computer vision, and graphics. The conventions in this section assume Hamilton (right-handed) quaternions and right-handed coordinate frames, which is what Eigen, ROS, GTSAM, Sophus, and most of robotics use.
7.1 Rotation Representations
| Type | Storage | Best for |
|---|---|---|
Matrix3d |
9 doubles | Composition, rotating vectors (one matvec), interop with linear-algebra code |
Quaterniond |
4 doubles | Smooth interpolation (slerp), no gimbal lock, compact, the right thing to store on disk |
AngleAxisd |
4 doubles (angle + axis) | Human-readable construction, small rotations as a tangent-space step |
Euler angles (Vector3d of eulerAngles) |
3 doubles | Intuition, configs, RPY for humans — avoid internally (gimbal lock, convention chaos) |
// Constructors
AngleAxisd aa(M_PI / 4, Vector3d::UnitZ()); // 45° about +Z
Quaterniond q(aa); // from axis-angle
Matrix3d R = q.toRotationMatrix();
// Apply to a point
Vector3d p(1, 0, 0);
Vector3d p_rotated = q * p; // overloaded * for unit quats
Vector3d p_rotated_alt = R * p;
// Interpolation between two orientations (slerp)
Quaterniond q0 = Quaterniond::Identity();
Quaterniond q1(aa);
Quaterniond q_mid = q0.slerp(0.5, q1);
7.2 Quaternion Storage: wxyz vs xyzw
This catches everyone exactly once. There are two conventions for the order of a unit quaternion's four components, and Eigen uses one in its constructor and the other in its internal storage:
| Where | Order |
|---|---|
Quaterniond(w, x, y, z) constructor (and .w(), .x(), .y(), .z() accessors) |
w, x, y, z — scalar first |
Quaterniond::coeffs() (4-vector), and the underlying contiguous memory |
x, y, z, w — scalar last |
Quaterniond q(0.7071, 0.0, 0.0, 0.7071); // w=0.7071, x=0, y=0, z=0.7071
std::cout << q.w() << " " << q.x() << " "
<< q.y() << " " << q.z() << '\n'; // 0.7071 0 0 0.7071
Vector4d v = q.coeffs();
// v == (x=0, y=0, z=0.7071, w=0.7071) -- xyzw order!
This matters when serializing or interoperating with another library:
- ROS
geometry_msgs/Quaternion: serialized as(x, y, z, w). Same byte order asq.coeffs(). Build withQuaterniond q(msg.w, msg.x, msg.y, msg.z). - glm:
glm::quat(w, x, y, z)constructor matches Eigen's constructor. - Unity / DirectX / many graphics APIs:
(x, y, z, w). Matchcoeffs(). - JSON / YAML: write down which order you're using; never pass a 4-tuple of numbers without naming it.
For axis-angle pairs, by contrast, the convention is universal: angle first, axis second.
A common-sense check after deserializing: a unit quaternion has q.norm() == 1 and applying it to a known vector produces the expected rotation. If q.norm() is off or the rotation comes out wrong, it's almost always the order convention.
7.3 Axis-Angle
AngleAxisd(angle, axis) represents a rotation by angle (radians) around the unit axis. The right-hand rule applies — fingers curl in the direction of positive rotation.
AngleAxisd aa(0.1, Vector3d::UnitZ()); // 0.1 rad ≈ 5.73° about +Z
// Convert to/from
Quaterniond q(aa);
Matrix3d R = aa.toRotationMatrix();
AngleAxisd aa_back(R); // canonical form: angle in [0, π]
// Compose three axis-aligned rotations explicitly
Quaterniond q_rpy =
AngleAxisd(yaw, Vector3d::UnitZ()) *
AngleAxisd(pitch, Vector3d::UnitY()) *
AngleAxisd(roll, Vector3d::UnitX()); // Z-Y-X intrinsic
Axis-angle is the natural representation for small rotations (the tangent space of SO(3) at the identity is just axis * angle), so it shows up in IMU integration, gradient steps in pose optimization, and exponential maps:
Vector3d omega_dt = ...; // small rotation as 3-vector (axis * angle)
double angle = omega_dt.norm();
Quaterniond dq = (angle < 1e-9)
? Quaterniond::Identity()
: Quaterniond(AngleAxisd(angle, omega_dt / angle));
q = q * dq; // integrate rotation
q.normalize(); // periodically re-normalize to combat drift
7.4 Conversions Between Representations
Matrix3d R = q.toRotationMatrix();
Quaterniond q2(R); // matrix → quat
AngleAxisd aa2(q); // quat → axis-angle
AngleAxisd aa3(R); // matrix → axis-angle
// Euler (use sparingly; read the convention!)
Vector3d ypr = R.eulerAngles(2, 1, 0); // intrinsic Z-Y-X
The argument to eulerAngles(a, b, c) is the order of axes — (0, 1, 2) is XYZ, (2, 1, 0) is ZYX, etc. The result is intrinsic, in radians, with the second-axis angle returned in [0, π] (so XZX-style "first and third axis the same" decompositions are well-defined). Document which convention your codebase uses or it will turn into a Friday afternoon debugging session.
7.5 Composing Rotations
Rotations compose by multiplication, right-to-left (the rightmost rotation is applied first):
// "rotate first by a, then by b" applied to vector v:
Quaterniond ab = b * a;
Vector3d out = ab * v; // == b * (a * v)
For unit quaternions, the inverse is the conjugate:
Quaterniond q_inv = q.conjugate(); // == q.inverse() for unit quats
q.conjugate() is faster than q.inverse() (no division), and the two agree as long as the quaternion is unit. If you're unsure, q.normalize() first.
7.6 Rigid Transforms and SLAM Patterns
For rotation + translation together, use Isometry3d (or its parent Affine3d). Isometry3d is exactly the rigid-body transform group SE(3) — what SLAM calls a "pose."
Isometry3d T_world_body = Isometry3d::Identity();
T_world_body.linear() = q.toRotationMatrix(); // 3×3 rotation block
T_world_body.translation() = Vector3d(1, 2, 3);
Vector3d p_body = ...;
Vector3d p_world = T_world_body * p_body; // applies R then t
Isometry3d T_body_world = T_world_body.inverse(); // exact, not LU
A few patterns that come up constantly in SLAM:
Compose poses along a chain. A common bug is doing this left-to-right:
// T_W_C: pose of camera in world; T_C_L: pose of LiDAR relative to camera
Isometry3d T_W_L = T_W_C * T_C_L; // correct
Vector3d p_W = T_W_L * p_lidar;
The "frame-on-frame" naming (T_A_B reads "B in A") makes the chain rule mechanical: subscripts cancel inwards. T_W_C * T_C_L = T_W_L.
Transforming a point cloud. For N points stored as a 3×N matrix:
Matrix<double, 3, Eigen::Dynamic> P_body = ...; // 3×N
Matrix<double, 3, Eigen::Dynamic> P_world =
(T_world_body.linear() * P_body).colwise() + T_world_body.translation();
Or with Isometry3d directly on each column (clearer, equally fast):
Matrix<double, 3, Eigen::Dynamic> P_world(3, N);
for (int i = 0; i < N; ++i) P_world.col(i) = T_world_body * P_body.col(i);
Homogeneous coordinates for 3D points are 4-vectors (x, y, z, 1) and let you express affine transforms (rotation + translation) as a single 4×4 matrix multiply. Eigen has direct helpers:
Vector3d p(1, 2, 3);
Vector4d p_h = p.homogeneous(); // (1, 2, 3, 1)
Vector3d p_back = p_h.hnormalized(); // (1, 2, 3) (divides by last component)
// Apply a 4x4 transform stored as Matrix4d
Matrix4d M = T_world_body.matrix();
Vector4d p_world_h = M * p.homogeneous();
Vector3d p_world = p_world_h.hnormalized();
Homogeneous form is mostly useful for projective transforms (camera projection, NDC), where the perspective divide in hnormalized() actually does work. For pure rigid motion, multiplying with Isometry3d is cleaner and avoids the divide.
Storing and re-normalizing rotations. Repeatedly composing rotations accumulates floating-point drift; the result slowly stops being orthonormal (for matrices) or unit (for quaternions). After many compositions, re-orthogonalize:
q.normalize(); // unit quaternion
// or for a rotation matrix: re-orthogonalize via SVD
JacobiSVD<Matrix3d> svd(R, ComputeFullU | ComputeFullV);
Matrix3d R_clean = svd.matrixU() * svd.matrixV().transpose();
For long-running SLAM systems, normalize every few hundred frames or after every optimization step. Quaternions drift much more slowly than matrices, which is one reason SLAM front-ends keep state as (translation, quaternion) even when computations end up using matrices.
8. Aliasing and .eval()
Eigen evaluates expression trees lazily and writes the result coefficient-by-coefficient. If the destination overlaps with the source, you can read a coefficient that has already been overwritten. This is an aliasing bug.
// BUG: reading transposed entries from M while writing to M
MatrixXd M = MatrixXd::Random(3, 3);
M = M.transpose(); // wrong result, no warning
For most operations Eigen detects the aliasing pattern at compile time and inserts a temporary automatically (matrix products do this); but for transpose, blocks, and reverse, the user has to opt in:
M = M.transpose().eval(); // forces evaluation into a temporary first
M.transposeInPlace(); // in-place version that handles aliasing
Other *InPlace helpers exist for reverse, adjoint, and a few more. Run with -DEIGEN_RUNTIME_NO_MALLOC and eigen_assert enabled in tests to catch many aliasing issues early.
The flip side: when you know there's no aliasing (most matrix products into a fresh destination), use noalias() to skip the safety temporary:
C.noalias() = A * B; // no internal temporary
This is a measurable win for hot loops doing many matrix-matrix multiplications.
9. The auto Pitfall with Expression Templates
Because Eigen returns expression objects, not matrices, auto captures the expression, not the value. If the inputs to that expression go out of scope or are mutated, the cached expression points at garbage.
// BUG: auto deduces an expression, not a Matrix.
auto E = A + B; // E is an Eigen::CwiseBinaryOp<...>, not a Matrix
A.setZero(); // mutating A invalidates anything E referenced
std::cout << E; // wrong values
The same trap shows up with temporaries:
// BUG: temporary B*c is gone after the line, but E refers into it.
auto E = (B * c).transpose();
use(E); // dangling expression
Fix: never use auto for the result of an Eigen expression unless you really do want the lazy expression. Store concrete types:
MatrixXd E = A + B; // forces evaluation
Vector3d e = (B * c).transpose(); // ditto
auto E_lazy = (A + B).eval(); // explicit eval -> Matrix
Eigen documents this prominently as the auto keyword pitfall. Treat it as a project-wide rule.
10. References
- Eigen main site — downloads, news.
- Eigen Documentation — API reference and topical guides.
- Quick Reference Guide — dense matrix operations cheat sheet.
- Geometry Module — rotations, transforms.
- Common Pitfalls (
auto, aliasing, alignment) — required reading. - Catalogue of Decompositions and Solvers — picking a solver.