Goal
Detect inner X-junction corners of a planar chessboard in a grayscale image and assemble them into one or more chessboard graphs. Input: a grayscale image on pixel domain ; optionally an expected pattern shape . Output: a set of chessboard graphs, each an ordered grid of subpixel corner coordinates with the per-corner pyramid level. The detector targets high-resolution images, focus and motion blur, harsh lighting, and background clutter. Single-scale x-corner intensity functions degrade rapidly as the X-junction smears across pixels; this method evaluates the same intensity over every level of an image pyramid and selects, per corner, the level at which the corner is best resolved.
Algorithm
Symbols.
- — pyramid image at level , with at full resolution and a 2× downsample of .
- — sixteen ring samples around a candidate pixel, indexed cyclically (Figure 1 of the paper).
- — eight three-sample group sums constructed from .
- — x-corner intensity at corner candidate on level .
- — corner contrast magnitude returned by the spoke orientation pass.
- , — perpendicular and longitudinal edge errors at the -th sample on a candidate edge.
The eight group sums combine three consecutive ring samples each. Four groups are aligned with the cardinal directions on the ring, four are rotated by :
A symmetric four-point response that fires when opposite groups straddle the local mean by the same sign:
Subtracting the local mean before the products yields affine lighting invariance.
The ring response at a candidate pixel; partial rotation invariance comes from taking the maximum of two templates offset by :
Given a corner observed at one or more levels with intensities , the chosen level is the one that maximises intensity per resolution:
The denominator penalises higher pyramid levels and the maximum trades the strength of the corner response against its localisation precision at that scale.
For an edge between corners and , sample point pairs across the edge at spacing determined by the pyramid levels of and . The perpendicular error measures intensity contrast across the edge and is maximised by high contrast; the longitudinal error measures intensity similarity along the edge. Both arrays are sorted and the worst entries discarded. The edge score is
Level-dependent spacing keeps samples away from the smeared centre of edges incident to blurred corners; constant spacing produces a uniformly low score regardless of whether an edge exists.
Procedure
- Build the pyramid .
- For each level :
- Convert to grayscale and rescale to ; apply a Gaussian blur.
- For every interior pixel, sample the sixteen ring values and compute the x-corner intensity .
- Convolve with a box kernel and apply a pixel offset to break the symmetric two-maximum pattern of an ideal X-junction.
- Apply non-maximum suppression to .
- Cascade filters: (a) reject pixels with below times the maximum on the top pyramid level; (b) reject if too many neighbours have positive ; (c) reject if the local up-down grayscale pattern around the corner is wrong; (d) Shi-Tomasi eigenvalue test on the structure tensor.
- Mean-shift refinement of each surviving corner in the intensity image.
- Compute orientation by integrating along spokes; pair each spoke with the one offset by and smooth the resulting array with a Gaussian kernel; the orientation is the smoothed maximum, and the corner contrast is the magnitude of the best-orientation spoke difference.
- For each persistent corner , set from the level-selection rule.
- For each corner , find its nearest neighbours in the same pyramid level or higher. For each :
- Discard if the orientations of and are not perpendicular.
- Sample a grid of points connecting and at level-dependent spacing.
- Compute the edge score ; keep the connection if exceeds threshold.
- For each corner, vote on its connected neighbours; resolve ambiguity by selecting the connection that best fits perspective geometry and grid topology.
- Discard ambiguous corners with insufficient votes.
- Enforce grid graph properties: every corner must have , , or neighbours, and two adjacent neighbours must share exactly one common corner. Prune connections that violate either property.
- Reorder each grid graph into a counter-clockwise chessboard graph: assign axes from corner orientation, anchor to a corner square, and trim outer rows or columns with missing corners.
- If the pattern shape is given, return only chessboard graphs of that shape; otherwise return all valid graphs.
Implementation
The per-pixel x-corner intensity in Rust:
fn xscore(v1: f32, v2: f32, v3: f32, v4: f32) -> f32 {
let mu = 0.25 * (v1 + v2 + v3 + v4);
(v1 - mu) * (v3 - mu) + (v2 - mu) * (v4 - mu)
}
fn x_corner_intensity(ring: &[f32; 16]) -> f32 {
let a = ring[0] + ring[1] + ring[2];
let b = ring[4] + ring[5] + ring[6];
let c = ring[8] + ring[9] + ring[10];
let d = ring[12] + ring[13] + ring[14];
let e = ring[2] + ring[3] + ring[4];
let f = ring[6] + ring[7] + ring[8];
let g = ring[10] + ring[11] + ring[12];
let h = ring[14] + ring[15] + ring[0];
xscore(a, b, c, d).max(xscore(e, f, g, h))
}
The per-corner pyramid-level rule from Equation (2):
fn select_level(samples: &[(usize, f32)]) -> Option<usize> {
samples
.iter()
.max_by(|(la, ia), (lb, ib)| {
(ia / (*la as f32 + 1.0))
.partial_cmp(&(ib / (*lb as f32 + 1.0)))
.unwrap()
})
.map(|(level, _)| *level)
}
The intensity loop is the pixel hot path and is run once per pyramid level. Each call performs sixteen ring reads, eight three-element sums, two xscore evaluations, and one max — no trigonometry, no interpolation, no branches.
Remarks
- Complexity per pyramid level is for the intensity pass; summed across the pyramid this is .
- The level-selection rule is the central blur-handling mechanism. A corner that responds weakly at level because of motion or focus blur is recovered at the lowest level where the response per resolution is maximal; choosing level unconditionally yields noise-dominated subpixel coordinates.
- The box filter step is necessary because the two-template admits two adjacent local maxima at an ideal X-junction; without it, non-maximum suppression picks one arbitrarily and subpixel refinement is unstable.
- Sample spacing along candidate edges is set per edge from the pyramid levels of its endpoints. Constant spacing samples the smeared centre of edges incident to blurred corners and produces a uniformly low score regardless of whether an edge exists.
- The detector returns one or more chessboard graphs and rejects graphs that do not match the requested shape; self-identifying patterns are out of scope and must be decoded by a downstream stage.
- Output metadata includes the chosen pyramid level per corner. This can be repurposed for autofocus diagnostics, per-corner uncertainty estimates, or rejection of blur-induced false positives.
- Compared with ChESS: see When to choose ChESS over Pyramidal on the ChESS page, which hosts the comparison per the older-paper-hosts rule.
- Compared with ROCHADE: see When to choose ROCHADE over Pyramidal on the ROCHADE page, which hosts the comparison per the older-paper-hosts rule.
References
- P. Abeles. Pyramidal Blur Aware X-Corner Chessboard Detector. arXiv.13793, 2021. arxiv.org/abs/2110.13793
- 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
- S. Bennett, J. Lasenby. ChESS — Quick and Robust Detection of Chess-board Features. arXiv.5491, 2013. arxiv.org/abs/1301.5491
- 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
- J. Shi, C. Tomasi. Good Features to Track. IEEE CVPR, 1994. DOI: 10.1109/CVPR.1994.323794