calibration_boards

Calibration board utilities.

This module defines calibration board utilities and classes used for camera and hand-eye calibration workflows. It provides board abstractions for ChArUco and checkerboard targets, board detection and pose estimation helpers, point correspondence generation, intrinsics result models, and persistence/export helpers for calibration artifacts. The module also includes visualization and validation utilities for robust calibration data processing.

Key functionalities include: - ChArUco and checkerboard board modeling and rendering. - Board detection and corner extraction from images. - Object/image point reference generation for calibration. - Board pose estimation and visualization utilities. - Camera intrinsics result representation and JSON serialization. - Helpers for calibration data storage and compatibility with OpenCV calibration pipelines.

robotblockset.cameras.calibration_boards.display_detection_results(image_of_board: ndarray, original_board: ndarray, detection_results: BoardDetectionResults, point_references: PointReferences) None[source]

Plot detected board corners against the reference board image.

Parameters:
  • image_of_board (OpenCVIntImageType) – Captured board image.

  • original_board (OpenCVIntImageType) – Reference board image.

  • detection_results (BoardDetectionResults) – Marker and corner detections.

  • point_references (PointReferences) – Object and image point correspondences.

Return type:

None

class robotblockset.cameras.calibration_boards.BoardDetectionResults(charuco_corners: np.ndarray | None, charuco_ids: np.ndarray | None, aruco_corners: np.ndarray | None, aruco_ids: np.ndarray | None)[source]

Bases: NamedTuple

Aggregated marker and corner detections for a calibration board.

Create new instance of BoardDetectionResults(charuco_corners, charuco_ids, aruco_corners, aruco_ids)

charuco_corners: ndarray | None

Alias for field number 0

charuco_ids: ndarray | None

Alias for field number 1

aruco_corners: ndarray | None

Alias for field number 2

aruco_ids: ndarray | None

Alias for field number 3

class robotblockset.cameras.calibration_boards.BoardPose(rvec: np.ndarray | None, tvec: np.ndarray | None)[source]

Bases: NamedTuple

Board pose represented by OpenCV rotation and translation vectors.

Create new instance of BoardPose(rvec, tvec)

rvec: ndarray | None

Alias for field number 0

tvec: ndarray | None

Alias for field number 1

as_homogeneous_matrix() ndarray | None[source]

Convert extrinsics to a homogeneous matrix.

Convert (rvec, tvec) to a 4x4 homogeneous transformation matrix.

as_pose() ndarray | None[source]

Convert (rvec, tvec) to a array (7,) - pose + quaternion.

class robotblockset.cameras.calibration_boards.PointReferences(object_points: np.ndarray, image_points: np.ndarray)[source]

Bases: NamedTuple

Matched object/image point references used in calibration.

Create new instance of PointReferences(object_points, image_points)

object_points: ndarray

Alias for field number 0

image_points: ndarray

Alias for field number 1

class robotblockset.cameras.calibration_boards.Resolution(*args: Any, **kwargs: Any)[source]

Bases: BaseModel

Image resolution in pixels.

width: int
height: int
as_tuple() Tuple[int, int][source]

Return resolution as (width, height) tuple.

Returns:

Resolution tuple.

Return type:

CameraResolutionType

class robotblockset.cameras.calibration_boards.FocalLengths(*args: Any, **kwargs: Any)[source]

Bases: BaseModel

Camera focal lengths in pixels.

fx: float
fy: float
class robotblockset.cameras.calibration_boards.PrincipalPoint(*args: Any, **kwargs: Any)[source]

Bases: BaseModel

Camera principal point in pixels.

cx: float
cy: float
class robotblockset.cameras.calibration_boards.CameraIntrinsics(*args: Any, **kwargs: Any)[source]

Bases: BaseModel

A format for storing the camera intrinsics at a specific image resolution.

image_resolution: Resolution
focal_lengths_in_pixels: FocalLengths
principal_point_in_pixels: PrincipalPoint
radial_distortion_coefficients: RadialDistortionCoefficients | None = None
tangential_distortion_coefficients: TangentialDistortionCoefficients | None = None
classmethod from_matrix_and_resolution(intrinsics_matrix: ndarray, resolution: Tuple[int, int]) CameraIntrinsics[source]

Build intrinsics from matrix and resolution.

Creates a CameraIntrinsics object from a 3x3 matrix and an image resolution (width, height).

as_matrix() ndarray[source]

Return the intrinsics matrix.

Returns the camera intrinsics as a 3x3 matrix, often called K.

class robotblockset.cameras.calibration_boards.CameraIntrinsicCalibrationResults(repError: float, camMatrix: ndarray, distcoeff: ndarray, rvecs: ndarray, tvecs: ndarray, image_size: Tuple[int, int])[source]

Bases: object

Container for OpenCV intrinsic calibration outputs.

repError: float
camMatrix: ndarray
distcoeff: ndarray
rvecs: ndarray
tvecs: ndarray
image_size: Tuple[int, int]
to_camera_intrinsics(include_distortion: bool = True) CameraIntrinsics[source]

Convert OpenCV calibration output (K, dist) to your CameraIntrinsics model.

Parameters:

include_distortion (bool, optional) – bool, default=True If True, include radial and tangential distortion coefficients extracted from distcoeff.

Returns:

Camera intrinsics model built from camMatrix and image_size.

Return type:

CameraIntrinsics

write_intrinsics_json(camera: str, stream: str, out_dir: str | Path = '.', include_distortion: bool = True) Path[source]

Write camera intrinsics to <camera>_<stream>_intrinsic_calibration.json.

Parameters:
  • camera (str) – Camera name used in the output filename.

  • stream (str) – Stream identifier used in the output filename.

  • out_dir (Union[str, Path], optional) – str or Path, default=”.” Output directory.

  • include_distortion (bool, optional) – bool, default=True If True, include distortion coefficients in the saved payload.

Returns:

Full path to the saved JSON file.

Return type:

Path

class robotblockset.cameras.calibration_boards.CharucoBoard(squares_x: int = 7, squares_y: int = 5, square_length_m: float = 0.04, marker_length_m: float = 0.031, margin_size_m: float = 0.0, scale_px_per_m: float = 1000.0, dictionary_id: int = cv2.aruco.DICT_4X4_50, min_corners: int = 10)[source]

Bases: object

ChArUco board wrapper for OpenCV 4.11.

  • Uses meters internally by default.

  • Builds cv2.aruco objects in __post_init__ so the instance is always ready to use.

  • margin_size_m and scale_px_per_m are per-instance fields (not class vars).

  • Includes unit helpers and a nice repr.

type = 1
squares_x: int = 7
squares_y: int = 5
square_length_m: float = 0.04
marker_length_m: float = 0.031
margin_size_m: float = 0.0
scale_px_per_m: float = 1000.0
min_corners: int = 10
dictionary: Any
board: Any
detector: Any
aruco_params: Any
charuco_params: Any
property size: Tuple[int, int]

Return board size as (squares_x, squares_y).

Returns:

Number of squares along X and Y.

Return type:

tuple[int, int]

detect(gray_image: ndarray) BoardDetectionResults | None[source]

Detect ChArUco board in a grayscale image.

Parameters:

gray_image (OpenCVIntImageType) – Input grayscale image with shape (H, W). If a color image is provided, it is converted to grayscale.

Returns:

Detection result containing ChArUco and ArUco corners/ids, or None when no valid board detection is found.

Return type:

BoardDetectionResults or None

get_poses_of_aruco_markers(detection_result: BoardDetectionResults, camera_matrix: ndarray, dist_coeffs: ndarray | None = None) List[ndarray] | None[source]

Estimate poses of detected ArUco markers.

Parameters:
  • detection_result (BoardDetectionResults) – Detection result containing ArUco corners and ids.

  • camera_matrix (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • dist_coeffs (np.ndarray, optional) – Distortion coefficients passed to pose estimation.

Returns:

Marker poses as homogeneous transforms, or None when pose estimation fails.

Return type:

list[HomogeneousMatrixType] or None

detectPose(gray_image: ndarray, camera_matrix: ndarray, dist_coeffs: ndarray | None = None, board_detection: BoardDetectionResults | None = None) BoardPose | None[source]

Detect checkerboard pose in a grayscale image.

Parameters:
  • gray_image (OpenCVIntImageType) – Input grayscale image with shape (H, W). If a color image is provided, it is converted to grayscale.

  • camera_matrix (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • dist_coeffs (np.ndarray, optional) – Distortion coefficients passed to cv2.solvePnP.

  • board_detection (BoardDetectionResults, optional) – Precomputed board detections to reuse instead of running detection.

Returns:

Estimated board pose, or None if pose estimation fails.

Return type:

BoardPose or None

drawFrame(image_bgr: ndarray, pose: BoardPose | ndarray, camera_matrix: ndarray, dist_coeffs: ndarray | None = None, length: float = 0.1) ndarray[source]

Draw board coordinate frame on a BGR image.

Parameters:
  • image_bgr (OpenCVIntImageType) – Input image.

  • pose (Union[BoardPose, Pose3DType, HomogeneousMatrixType]) – Pose to render.

  • camera_matrix (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • dist_coeffs (np.ndarray, optional) – Distortion coefficients.

  • length (float, optional) – float, default=0.1 Axis length in meters.

Returns:

Annotated image.

Return type:

np.ndarray

drawDetection(image_bgr: ndarray, board_detection: BoardDetectionResults, draw_aruco: bool = True, draw_charuco: bool = True) ndarray[source]

Draw detected ArUco and/or ChArUco corners on an image.

Parameters:
  • image_bgr (OpenCVIntImageType) – Input BGR image.

  • board_detection (BoardDetectionResults) – Detection result containing corners and ids.

  • draw_aruco (bool, optional) – bool, default=True Draw ArUco marker outlines when available.

  • draw_charuco (bool, optional) – bool, default=True Draw ChArUco corners when available.

Returns:

Annotated BGR image.

Return type:

np.ndarray

image(margin_size_m: float | None = None, scale_px_per_m: float | None = None) ndarray[source]

Render the ChArUco board as an image.

Parameters:
  • margin_size_m (float, optional) – Margin around the board in meters. If None, instance default is used.

  • scale_px_per_m (float, optional) – Rendering scale in pixels per meter. If None, instance default is used.

Returns:

Rendered board image.

Return type:

np.ndarray

intrinsic_calibration(images: List[ndarray], calibration_flags: int = 0, silent: bool = True, K_init: ndarray | None = None, dist_init: ndarray | None = None, refine: bool = True, freeze_principal_point: bool = False, freeze_focal_length: bool = False, fix_aspect_ratio: bool = False, zero_tangent_dist: bool = False, fix_k: List[int] | None = None) CameraIntrinsicCalibrationResults[source]

Intrinsic calibration using OpenCV 4.11 ChArUcoDetector.

Parameters:
  • images (List[OpenCVIntImageType]) – Calibration images containing the board.

  • calibration_flags (int, optional) – int, default=0 Additional OpenCV calibration flags.

  • silent (bool, optional) – bool, default=True If False, show detection visualization while collecting points.

  • K_init (np.ndarray, optional) – Initial 3x3 intrinsics matrix.

  • dist_init (np.ndarray, optional) – Initial distortion coefficients.

  • refine (bool, optional) – bool, default=True If True, refine provided intrinsics/distortion as initial guess. If False, keep provided intrinsics fixed.

  • freeze_principal_point (bool, optional) – bool, default=False Apply cv2.CALIB_FIX_PRINCIPAL_POINT.

  • freeze_focal_length (bool, optional) – bool, default=False Apply cv2.CALIB_FIX_FOCAL_LENGTH.

  • fix_aspect_ratio (bool, optional) – bool, default=False Apply cv2.CALIB_FIX_ASPECT_RATIO (requires K_init).

  • zero_tangent_dist (bool, optional) – bool, default=False Apply cv2.CALIB_ZERO_TANGENT_DIST.

  • fix_k (List[int], optional) – Distortion coefficient indices to fix (values in 1..6).

Returns:

OpenCV calibration output (RMS, K, distortion, rvecs, tvecs, image size).

Return type:

CameraIntrinsicCalibrationResults

Notes

With refine=True, K_init/dist_init are used as initial guesses via cv2.CALIB_USE_INTRINSIC_GUESS. With refine=False, intrinsics are fixed using cv2.CALIB_FIX_INTRINSIC.

extrinsic_calibration_all_methods(results_dir: str, images: List[ndarray], tcp_poses_in_base: List[ndarray], intrinsics: ndarray, mode: str = 'eye_in_hand') Tuple[Dict[str, Any], Dict[str, float]][source]

Run all OpenCV extrinsic calibration methods.

Computes the calibration solution for all methods available in OpenCV and saves the results to a directory.

Parameters:
  • results_dir (str) – Directory to save calibration outputs. It must already exist.

  • images (List[OpenCVIntImageType]) – Captured calibration-board images.

  • tcp_poses_in_base (List[HomogeneousMatrixType]) – TCP poses in the robot base frame.

  • intrinsics (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • mode (str, optional) – Calibration mode, either "eye_in_hand" or "eye_to_hand".

Returns:

Two dictionaries: estimated camera poses per method and residual calibration errors per method.

Return type:

tuple[dict[str, Any], dict[str, float]]

classmethod from_mm(*, squares_x: int = 7, squares_y: int = 5, square_length_mm: float = 40.0, marker_length_mm: float = 31.0, margin_size_mm: float = 0.0, dictionary_id: int = cv2.aruco.DICT_4X4_50, min_corners: int = 10, scale_px_per_mm: float = 1.0) CharucoBoard[source]

Construct a board using millimeters.

Parameters:
  • squares_x (int, optional) – int, default=7 Number of board squares along X.

  • squares_y (int, optional) – int, default=5 Number of board squares along Y.

  • square_length_mm (float, optional) – float, default=40.0 Square size in millimeters.

  • marker_length_mm (float, optional) – float, default=31.0 Marker size in millimeters.

  • margin_size_mm (float, optional) – float, default=0.0 Rendering margin in millimeters.

  • dictionary_id (int, optional) – int, default=cv2.aruco.DICT_4X4_50 OpenCV ArUco dictionary id.

  • min_corners (int, optional) – int, default=10 Minimum detected corners required for use.

  • scale_px_per_mm (float, optional) – float, default=1.0 Rendering scale; 1.0 means 1 pixel per millimeter.

Returns:

Configured board instance.

Return type:

CharucoBoard

as_mm() dict[source]

Return board geometry expressed in millimeters.

Returns:

Dictionary containing board geometry and configuration values.

Return type:

dict

class robotblockset.cameras.calibration_boards.CheckerBoard(cols: int = 7, rows: int = 6, square_length_m: float = 0.0104, use_sb: bool = True, refine_subpix: bool = True, fast_check: bool = True, subpix_win: Tuple[int, int] = (11, 11), subpix_criteria: Tuple[int, int, float] = (3, 30, 0.001), margin_size_m: float = 0.0, scale_px_per_m: float = 1000.0)[source]

Bases: object

Checkerboard (classic chessboard) wrapper.

  • Uses meters internally by default.

  • Provides detection via findChessboardCornersSB (robust) with optional subpixel refinement.

  • Provides object points for solvePnP/calibration.

  • Includes unit helpers and a nice repr.

Notes

pattern_size uses INNER corners: cols is the number of inner corners along X (width), and rows is the number of inner corners along Y (height).

type = 0
cols: int = 7
rows: int = 6
square_length_m: float = 0.0104
use_sb: bool = True
refine_subpix: bool = True
fast_check: bool = True
subpix_win: Tuple[int, int] = (11, 11)
subpix_criteria: Tuple[int, int, float] = (3, 30, 0.001)
min_corners = 10
margin_size_m: float = 0.0
scale_px_per_m: float = 1000.0
property pattern_size: Tuple[int, int]

Return checkerboard inner-corner pattern size.

Returns:

Pattern size as (cols, rows).

Return type:

tuple[int, int]

property object_points: ndarray

Return checkerboard object points in board coordinates.

Returns:

Object points with shape (N, 3) in meters.

Return type:

np.ndarray

detect(gray_image: ndarray) BoardDetectionResults[source]

Detect checkerboard corners in a grayscale image.

Parameters:

gray_image (OpenCVIntImageType) – Input grayscale image with shape (H, W). If a color image is provided, it is converted to grayscale.

Returns:

Detection result with checkerboard corners in charuco_corners (shape (N, 1, 2)) and synthetic ids in charuco_ids (shape (N, 1)), or None fields if not found.

Return type:

BoardDetectionResults

detectPose(gray_image: ndarray, camera_matrix: ndarray, dist_coeffs: ndarray | None = None, board_detection: BoardDetectionResults | None = None) BoardPose | None[source]

Detect checkerboard pose in a grayscale image.

Parameters:
  • gray_image (OpenCVIntImageType) – Input grayscale image with shape (H, W). If a color image is provided, it is converted to grayscale.

  • camera_matrix (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • dist_coeffs (np.ndarray, optional) – Distortion coefficients passed to cv2.solvePnP.

  • board_detection (BoardDetectionResults, optional) – Precomputed board detections to reuse instead of running detection.

Returns:

Estimated board pose, or None if pose estimation fails.

Return type:

BoardPose or None

drawFrame(image_bgr: ndarray, pose: BoardPose | ndarray, camera_matrix: ndarray, dist_coeffs: ndarray | None = None, length: float = 0.1) ndarray[source]

Draw checkerboard coordinate frame on a BGR image.

Parameters:
  • image_bgr (OpenCVIntImageType) – Input image.

  • pose (Union[BoardPose, Pose3DType, HomogeneousMatrixType]) – Pose to render.

  • camera_matrix (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • dist_coeffs (np.ndarray, optional) – Distortion coefficients.

  • length (float, optional) – float, default=0.1 Axis length in meters.

Returns:

Annotated image.

Return type:

np.ndarray

drawDetection(image_bgr: ndarray, board_detection: BoardDetectionResults, found: bool = True) ndarray[source]

Draw detected checkerboard corners on an image.

Parameters:
  • image_bgr (OpenCVIntImageType) – Input BGR image.

  • board_detection (BoardDetectionResults) – Detection result containing checkerboard corners.

  • found (bool, optional) – bool, default=True Status flag forwarded to OpenCV drawing utility.

Returns:

Annotated BGR image.

Return type:

np.ndarray

image(margin_size_m: float | None = None, scale_px_per_m: float | None = None) ndarray[source]

Render a synthetic checkerboard image for printing/debugging. This is not required for detection, but mirrors CharucoBoard.image() usability.

Parameters:
  • margin_size_m (float, optional) – Margin around the rendered board in meters.

  • scale_px_per_m (float, optional) – Rendering scale in pixels per meter.

Returns:

Rendered checkerboard image.

Return type:

np.ndarray

Notes

The rendered board has (cols + 1) x (rows + 1) squares because cols and rows represent inner corners.

intrinsic_calibration(images: List[ndarray], calibration_flags: int = 0, silent: bool = True, K_init: ndarray | None = None, dist_init: ndarray | None = None, refine: bool = True, freeze_principal_point: bool = False, freeze_focal_length: bool = False, fix_aspect_ratio: bool = False, zero_tangent_dist: bool = False, fix_k: List[int] | None = None) CameraIntrinsicCalibrationResults[source]

Intrinsic calibration of a checkerboard dataset.

Parameters:
  • images (List[OpenCVIntImageType]) – Calibration images containing the board.

  • calibration_flags (int, optional) – int, default=0 Additional OpenCV calibration flags.

  • silent (bool, optional) – bool, default=True If False, show detection visualization while collecting points.

  • K_init (np.ndarray, optional) – Initial 3x3 intrinsics matrix.

  • dist_init (np.ndarray, optional) – Initial distortion coefficients.

  • refine (bool, optional) – bool, default=True If True, refine provided intrinsics/distortion as initial guess. If False, keep provided intrinsics fixed.

  • freeze_principal_point (bool, optional) – bool, default=False Apply cv2.CALIB_FIX_PRINCIPAL_POINT.

  • freeze_focal_length (bool, optional) – bool, default=False Apply cv2.CALIB_FIX_FOCAL_LENGTH.

  • fix_aspect_ratio (bool, optional) – bool, default=False Apply cv2.CALIB_FIX_ASPECT_RATIO (requires K_init).

  • zero_tangent_dist (bool, optional) – bool, default=False Apply cv2.CALIB_ZERO_TANGENT_DIST.

  • fix_k (List[int], optional) – Distortion coefficient indices to fix (values in 1..6).

Returns:

OpenCV calibration output (RMS, K, distortion, rvecs, tvecs, image size).

Return type:

CameraIntrinsicCalibrationResults

Notes

With refine=True, K_init/dist_init are used as initial guesses via cv2.CALIB_USE_INTRINSIC_GUESS. With refine=False, intrinsics are fixed using cv2.CALIB_FIX_INTRINSIC.

extrinsic_calibration_all_methods(results_dir: str, images: List[ndarray], tcp_poses_in_base: List[ndarray], intrinsics: ndarray, mode: str = 'eye_in_hand') Tuple[dict, dict][source]

Run all OpenCV extrinsic calibration methods.

Computes the calibration solution for all methods available in OpenCV and saves the results to a directory.

Parameters:
  • results_dir (str) – Directory to save calibration outputs. It must already exist.

  • images (List[OpenCVIntImageType]) – Captured calibration-board images.

  • tcp_poses_in_base (List[HomogeneousMatrixType]) – TCP poses in the robot base frame.

  • intrinsics (CameraIntrinsicsMatrixType) – Camera intrinsics matrix.

  • mode (str, optional) – Calibration mode, either "eye_in_hand" or "eye_to_hand".

Returns:

Two dictionaries: estimated camera poses per method and residual calibration errors per method.

Return type:

tuple[dict, dict]

classmethod from_mm(*, cols: int = 6, rows: int = 4, square_length_mm: float = 40.0, margin_size_mm: float = 0.0, scale_px_per_mm: float = 1.0, use_sb: bool = True, refine_subpix: bool = True, fast_check: bool = True) CheckerBoard[source]

Construct a checkerboard using millimeter units.

Parameters:
  • cols (int, optional) – int, default=6 Number of inner corners along X.

  • rows (int, optional) – int, default=4 Number of inner corners along Y.

  • square_length_mm (float, optional) – float, default=40.0 Square size in millimeters.

  • margin_size_mm (float, optional) – float, default=0.0 Rendering margin in millimeters.

  • scale_px_per_mm (float, optional) – float, default=1.0 Rendering scale; 1.0 means 1 pixel per millimeter.

  • use_sb (bool, optional) – bool, default=True Use cv2.findChessboardCornersSB when True.

  • refine_subpix (bool, optional) – bool, default=True Refine detected corners to subpixel precision.

  • fast_check (bool, optional) – bool, default=True Enable fast-check flag for classic corner detector.

Returns:

Configured checkerboard instance.

Return type:

CheckerBoard

as_mm() dict[source]

Return checkerboard geometry expressed in millimeters.

Returns:

Dictionary containing checkerboard geometry and detection settings.

Return type:

dict

Functions

display_detection_results(image_of_board, ...)

Plot detected board corners against the reference board image.

Classes

BoardDetectionResults(charuco_corners, ...)

Aggregated marker and corner detections for a calibration board.

BoardPose(rvec, tvec)

Board pose represented by OpenCV rotation and translation vectors.

CameraIntrinsicCalibrationResults(repError, ...)

Container for OpenCV intrinsic calibration outputs.

CameraIntrinsics(*args, **kwargs)

A format for storing the camera intrinsics at a specific image resolution.

CharucoBoard([squares_x, squares_y, ...])

ChArUco board wrapper for OpenCV 4.11.

CheckerBoard([cols, rows, square_length_m, ...])

Checkerboard (classic chessboard) wrapper.

FocalLengths(*args, **kwargs)

Camera focal lengths in pixels.

PointReferences(object_points, image_points)

Matched object/image point references used in calibration.

PrincipalPoint(*args, **kwargs)

Camera principal point in pixels.

Resolution(*args, **kwargs)

Image resolution in pixels.