Goal
Locate the inner corners of a planar checkerboard pattern in a grayscale image and return their subpixel coordinates. Input: a grayscale image and the pattern dimensions . Output: a set of subpixel corner coordinates ordered on the grid. The method tolerates extreme poses, lens distortion, low resolution, and non-uniform square sizes, but requires that the full pattern lies inside .
Algorithm
Let denote the grayscale image. Let denote a binary mask. Let denote the undirected graph induced by a thinned binary mask under -connectivity. Let denote the local-thresholding window radius. Let denote the saddle combination distance. Let denote the half-size of the cone filter kernel. Let denote the half-size of the surface-fitting window. Let denote the set of -connected neighbours of in the pixel grid.
A binary centreline mask with pixel thickness induces a graph whose vertices are the "true" pixels and whose edges connect -neighbours:
The saddle points of are the vertices of degree at least three:
Inner checkerboard corners map to such saddle points because four centreline segments meet at every X-junction.
A -D cone kernel with half-size and indices :
Convolving a step-function checkerboard with a sectionally linear kernel yields a sectionally defined bivariate quadratic, which a quadratic surface fit can represent exactly.
Let denote the cone-filtered image. In a window centred on an initial integer corner , fit the polynomial
by least squares against for . The refined corner is , where solves
The inequality enforces that the stationary point is a saddle (Hessian eigenvalues of opposite sign).
Procedure
- Optional: downsample to control processing time; the refinement step runs on the original resolution.
- Compute the Scharr gradient magnitude .
- In every window, set if the centre gradient lies in the upper of the window's intensity range; otherwise .
- Conditional dilation: for every with , set iff at least of satisfy .
- Reduce to a single-pixel centreline by distance-transform thinning. Interpret the result as .
- Extract . Prune dead-end paths: starting from every pixel with , delete vertices until a saddle is reached, except at the image border. Rethin to restore centreline thickness .
- Cluster by single-linkage with distance ; replace each cluster by its centroid. Start with and, if verification fails, increment to , , .
- For every connected component of with exactly cluster centroids: check that the induced adjacency between centroids matches the grid topology. If it does, pass the centroids as initial corners to the refinement step.
- For each initial corner : convolve with the cone kernel ; fit by least squares in the window around ; solve for ; accept iff .
Implementation
The subpixel kernel is the core computation: fit a bivariate quadratic to a cone-filtered window and solve for its saddle. The detection stages upstream are graph-bookkeeping and shell around this kernel.
fn cone_kernel(gamma: usize) -> Vec<f64> {
let size = 2 * gamma + 1;
let g = gamma as f64;
(0..size).flat_map(|i| (0..size).map(move |j| {
let d = ((g - i as f64).powi(2) + (g - j as f64).powi(2)).sqrt();
(g + 1.0 - d).max(0.0)
})).collect()
}
fn refine_saddle(f: &[f64], w: usize, x: usize, y: usize, kappa: usize) -> Option<(f64, f64)> {
let mut m = [[0.0f64; 6]; 6];
let mut b = [0.0f64; 6];
for di in -(kappa as i32)..=(kappa as i32) {
for dj in -(kappa as i32)..=(kappa as i32) {
let xi = di as f64;
let yj = dj as f64;
let v = f[(y as i32 + dj) as usize * w + (x as i32 + di) as usize];
let phi = [xi * xi, xi * yj, yj * yj, xi, yj, 1.0];
for r in 0..6 {
b[r] += phi[r] * v;
for c in 0..6 { m[r][c] += phi[r] * phi[c]; }
}
}
}
let a = solve_6x6(m, b)?;
let (a1, a2, a3, a4, a5) = (a[0], a[1], a[2], a[3], a[4]);
let det = 4.0 * a1 * a3 - a2 * a2;
if det >= 0.0 { return None; }
let dx = (a2 * a5 - 2.0 * a3 * a4) / det;
let dy = (a2 * a4 - 2.0 * a1 * a5) / det;
Some((x as f64 + dx, y as f64 + dy))
}
The cone filter is convolved with before refine_saddle runs; solve_6x6 is any dense symmetric solver (Cholesky on the normal matrix suffices because the Vandermonde-like design matrix has full column rank for ).
Remarks
- Stage 1 is per image: gradient, thresholding, dilation, centreline, and graph walks are all linear in pixel count; the cluster schedule is a constant-depth loop over .
- Stage 2 is per image: the quadratic fit is solved in closed form for each of corners.
- Detection requires the full pattern to be present. Partial visibility, occlusion, or pattern edges running outside fail step 8 because the inner-corner count no longer matches .
- Parameter dependence is local: sets the spatial scale of the edge-vs-flat decision; the threshold trades false-positive edges against missed edges on low-contrast images; collapses saddle multiplets produced by centreline imperfections at X-junctions; and must jointly exceed the radius over which the cone-convolved pattern is still piecewise quadratic — undersized leaves flat plateaux that the fit cannot localise.
- The cone kernel is preferred over a Gaussian because convolution of step-function checkerboards with a sectionally linear kernel produces sectionally defined bivariate quadratics, matching the fit exactly; a Gaussian smears the quadratic structure and biases the saddle location under anisotropic sampling.
- Dead-end pruning plus rethinning in step 6 eliminates degree- artefacts induced by short centreline spurs; without it, every spur branch contributes a spurious saddle at its root.
- The stage-1 graph is the input required by OCPAD to recover partially occluded patterns — OCPAD replaces step 8 with a VF2 subgraph-isomorphism search and the rest of the pipeline is reused verbatim.
- Compared with ChESS: see When to choose ChESS over ROCHADE on the ChESS page, which hosts the comparison per the older-paper-hosts rule.
When to choose ROCHADE over Pyramidal
Pyramidal blur-aware X-corner (Abeles 2021) computes a ChESS-style 16-sample template at every level of an image pyramid and selects per corner the level that maximises intensity-per-resolution. ROCHADE is a single-scale detector that achieves blur robustness through a different mechanism — the gradient-magnitude centreline survives heavy blur because the centreline graph is topological, not intensity-based.
| ROCHADE (2014) | Pyramidal (2021) | |
|---|---|---|
| Scale handling | single-scale | full image pyramid (typically 4–6 levels) |
| Blur strategy | centreline + cone-quadratic refinement | scale-pyramid + blur-aware edge validation |
| Per-image cost | one pass through the centreline pipeline | passes through the X-corner detector + edge validation |
| Subpixel accuracy | high (cone-quadratic) | high (mean-shift in intensity image) |
| Extreme-pose regime | strong (Mesa 91/103 vs OpenCV 8/103) | strong (per-corner level selection compensates for foreshortening) |
Choose ROCHADE when (1) the image is moderately blurred and the corner sizes are roughly known a priori — the single-scale pipeline is faster and well-tuned for the common machine-vision case; (2) the centreline-graph stage is useful as input to downstream pipelines like OCPAD (which reuses ROCHADE Stage 1 verbatim before applying VF2 subgraph isomorphism). Choose Pyramidal when corner sizes vary widely across a single image (close-range plus long-range targets), when the pipeline must work across extreme blur regimes (fast-moving scenes, motion blur), or when per-corner pyramid-level metadata is useful downstream (autofocus diagnostics, per-corner uncertainty estimates).
References
- S. Placht, P. Fürsattel, E. A. Mengue, H. Hofmann, C. Schaller, M. Balda, E. Angelopoulou. ROCHADE: Robust Checkerboard Advanced Detection for Camera Calibration. ECCV, 2014. DOI: 10.1007/978-3-319-10593-2_50
- L. Lucchese, S. K. Mitra. Using saddle points for subpixel feature detection in camera calibration targets. Asia Pacific Conference on Circuits and Systems, 2003. DOI: 10.1109/APCCAS.2002.1115151
- C. W. Niblack, P. B. Gibbons, D. W. Capson. Generating skeletons and centerlines from the distance transform. CVGIP: Graphical Models and Image Processing, 1992. DOI: 10.1016/1049-9652(92)90026-T
- M. Rufli, D. Scaramuzza, R. Siegwart. Automatic detection of checkerboards on blurred and distorted images. IEEE/RSJ IROS, 2008. DOI: 10.1109/IROS.2008.4650703
- D. Chen, G. Zhang. A New Sub-Pixel Detector for X-Corners in Camera Calibration Targets. WSCG Short Papers, 2005. PDF