collect_calibration_data
Calibration data collection utilities.
This module defines utilities for collecting camera-robot calibration datasets. It provides helpers for preparing calibration directories, acquiring synchronized image and robot TCP pose samples, saving calibration artifacts, and running interactive/manual collection loops with live board detection feedback. The module is designed to support reproducible hand-eye and camera calibration workflows.
Key functionalities include: - Creation and validation of calibration data directories. - Synchronized capture of camera images and robot TCP poses. - Persistent storage of image samples and pose metadata. - Camera intrinsics export for calibration session reproducibility. - Interactive and manual data collection loops. - Live ChArUco detection visualization during sample acquisition.
- robotblockset.cameras.collect_calibration_data.create_data_dir(calibration_dir: str | None = None) str[source]
Create an empty calibration data directory.
Ensures that
calibration_direxists and has adatasubfolder where new calibration samples can be stored.- Parameters:
calibration_dir (str, optional) – Calibration directory to use. If
None, a new directory is created in the current working directory.- Returns:
Path to the
datasubfolder of the calibration directory.- Return type:
str
- robotblockset.cameras.collect_calibration_data.save_calibration_sample(sample_index: int, robot: robot, camera: RGBCamera, data_dir: str) Tuple[ndarray, ndarray][source]
Save one calibration sample.
A calibration sample consists of an image and the robot TCP pose.
- Parameters:
- Returns:
Saved TCP pose and captured image.
- Return type:
Tuple[HomogeneousMatrixType, OpenCVIntImageType]
- robotblockset.cameras.collect_calibration_data.prepare_collect_calibration_data(camera: RGBCamera, calibration_dir: str | None) None[source]
Prepare hand-eye calibration data collection.
- Parameters:
camera (RGBCamera) – Camera to use for collecting the data.
calibration_dir (str, optional) – Directory where calibration data will be stored. If
None, a new directory is created.
- robotblockset.cameras.collect_calibration_data.manually_collect_calibration_data(robot: robot, camera: RGBCamera, calibration_dir: str | None) None[source]
Collect calibration data samples for hand-eye calibration.
Functions
|
Create an empty calibration data directory. |
|
Collect calibration data samples for hand-eye calibration. |
|
Prepare hand-eye calibration data collection. |
|
Save one calibration sample. |