\page calibration Calibration
Calibrating camera intrinsics involves generating target detection files from a set of bagfiles, generating or providing an initial estimate for the camera intrinsics and distortion values, and finally running the calibrator. Several camera distortion models (fov, rad, radtan) are supported for calibration and various scripts are provided to view the quality of the input target detections and the calibration results.
rosrun calibration save\_images\_with\_target\_detections -d ~/bag\_files -o target\_detections -t ~/target.yaml
Here ~/bag\_files
contains a directory of bagfiles containing target detection images.
rosrun calibration view\_all\_detections.py -d target\_detections
feh detection\_image.jpg
Ideally the target detections span the entire image. If only the middle of the image contains detections or if parts of the image have no detections, this may lead to an underconstrained calibration problem. Ensure good target coverage before attempting to calibrate a camera.
In addition to the script parameters, the camera_target_based_intrinsics_calibrator.config contains most of the configuration options for camera target based intrinsics calibration. The distortion model, camera name, parameters for the reprojection pose estimator handling target pose estimation, visualization, and other general parameters can be selected.
The parameters to calibrate can also be selected. Depending on the distortion model used, different parameters should be calibrated concurrently to avoid degeneracies and underconstrained calibration. For example, calibrating the camera principal points and target poses at the same time should be avoided. Calibration may be repeated while incrementally updating solved parameters and toggling different concurrent parameter sets to solve for until all parameters are adequately calibrated.
rosrun calibration calibrate\_intrinsics\_and\_save\_results.py target\_detections ~\/astrobee\/src\/astrobee\/config config\/robots\/bumble.config -u -p -i target\_detections -d fov
For more details of the calibration script see below in the Scripts section.
The calibrated results are saved in the calibrated_params.txt file while more verbose output is saved to the calibration_output.txt file.
Rely primarily on the covariances for each calibrated parameter reported at the end of the calibration_output.txt file.
The output calibrated_reprojection_from_all_targets_absolute_image.png displays reprojection errors after the calibration procedure has completed and can give a general sense of the calibration accuracy, although it does not discern between accurate calibration and overfitting, which is why the covariances mentioned previously should be the primary indicator of calibration accuracy.
Here reprojection errors are colored by the norm of the error on a continuous color spectrum, with dark blue indicated small/zero error and red indicating large error.
The generated error histogram (which displays the overall norm, x, and y errors on seperate plots) can be helpful to view overall error during calibration and to see if any bias exists in the errors. For example, if the x or y error histograms are not zero centered, this can indicate an error in the calibrated principal points.
This is generated by passing the -p option to the calibration script or by running the make_error_histograms.py script on the output errors.txt file after calibration has completed.
The undistorted images generated by passing -u to the calibration script or by seperately running the create_undistorted_images script give an additional indicator of calibration accuracy. Undistorted calibration targets should have straight boundary edges and straight lines within the target. Curved lines can indicate an error in the calibration distortion parameters.
Distorted Image:
Undistorted Image (FOV distortion):
The black dots in the undistorted image are a result of the FOV undistortion procedure, while the Rad and RadTan uses interpolation to fill these.
Generates undistorted images from a set of distorted images and provided camera calibration parameters. See 'rosrun calibration create_undistorted_images -h' for further details and usage instructions.
Runs the intrinsics calibrator using a set of target detection files and initial estimates for the camera intrinsics and distortion values. Support various distortion models. See 'rosrun calibration run_camera_target_based_intrinsics_calibrator -h' for further details and usage instructions.
Runs camera intrinsic calibration using provided target detections and a config file with camera parameters (including initial estimate for camera intrinsics and distortion values). See 'rosrun calibration calibrate_intrinsics_and_save_results.py -h' for further details and usage instructions.
Helper script that copies calibration parameters from the output of the calibration pipeline and writes these to the camera config file. See 'rosrun calibration copy_calibration_params_to_config.py -h' for further details and usage instructions.
Helper script that generates a list of bag files in a directory with the provided topic. See 'rosrun calibration get_bags_with_topic.py -h' for further details and usage instructions.
Generates a histogram of errors using the output errors from the calibration pipeline. See 'rosrun calibration make_error_histograms.py -h' for further details and usage instructions.
Generates target detection files for use with the calibration pipeline from a set of bagfiles containing images of target detections. See 'rosrun calibration save_images_with_target_detections.py -h' for further details and usage instructions.
Generates an image containing all images space detections of a target for a set of target detection files. See 'rosrun calibration view_all_detections.py -h' for further details and usage instructions.