-
Notifications
You must be signed in to change notification settings - Fork 4
Calibration
For the calibration of the fish-eye cameras several models are available:
- Unified Camera Model (C. Mei, and P. Rives, Single View Point Omnidirectional Camera Calibration from Planar Grids, ICRA 2007).
- Extended Unified Camera Model (B. Khomutenko, G. Garcia, P. Martinet, "An enhanced unified camera model", IEEE Robotics and Automation Letters, vol. 1, no. 1, pp. 137-144, Jan 2016).
- Double Sphere Camera Model (V. Usenko, N. Demmel and D. Cremers, "The Double Sphere Camera Model," 2018 International Conference on 3D Vision (3DV), Verona, 2018).
There are two software packages available for fish-eye camera calibration:
The steps of the calibration process are presented below for each package, but first we explain the process of obtaining the calibration data.
First, set the parameters of capture.launch to:
width=1280, height=720, frequency=1Hz, split=True, display=True
Next, launch the capture process and record the data with rosbag, e.g. 100 images:
roslaunch ricoh_camera capture.launch
rosbag record --bz2 --limit=100 --output-name=front_camera.bag /cam_1/image_front_raw
rosbag record --bz2 --limit=100 --output-name=back_camera.bag /cam_1/image_back_raw
The bags can be directly used in Kalibr; if using CamOdocal you should extract the images from the bags with:
rosrun image_view image_saver image:=/cam_1/image_back_raw \
_filename_format:="back%04d.png"
rosbag play back_camera.bag
rosrun image_view image_saver image:=/cam_1/image_front_raw \
_filename_format:="front%04d.png"
rosbag play front_camera.bag
We use a Docker container, with requisites:
- Docker >= 1.12
- nvidia-docker2 (Note that you need NVIDIA drivers)
After cloning the repository, you only need to run the command (UNIX systems):
./docker_helper.sh build
Move the recorded images from the back and front cameras to the folders:
calibration/camodocal/back_imagescalibration/camodocal/front_images
cd to calibration/camodocal and run the calibration script for each camera:
./camodocal_back.sh run "intrinsic_calib -w 8 -h 5 -s 0.03 \
--camera-model mei -i /root/input_data -p back -e .png --camera-name back"
./camodocal_front.sh run "intrinsic_calib -w 8 -h 5 -s 0.03 \
--camera-model mei -i /root/input_data -p front -e .png --camera-name front"
The results are stored in the output_data folder as:
back_camera_calib.yamlfront_camera_calib.yaml
Build Docker image with:
git clone https://github.com/davvdg/ros-kalibr.git
cd ros-kalibr
docker build -t ros-kalibr .
Alternatively, you can download an already-build image with:
docker pull davvdg/ros-kalibr
Move the recorded bags to calibration/kalibr, and run:
xhost +
roscd ricoh_camera/calibration/kalibr/
./run_kalibr_calibrate_cameras_in_docker.bash omni-radtan cam_1 back
./run_kalibr_calibrate_cameras_in_docker.bash omni-radtan cam_1 front
./run_kalibr_calibrate_cameras_in_docker.bash eucm-none cam_1 back
./run_kalibr_calibrate_cameras_in_docker.bash eucm-none cam_1 front
./run_kalibr_calibrate_cameras_in_docker.bash ds-none cam_1 back
./run_kalibr_calibrate_cameras_in_docker.bash ds-none cam_1 front
The results are stored in the folders omni-radtan (Unified Camera Model),
eucm-none (Extended Unified Camera Model), and ds-none (Double Sphere Camera Model).
Clone the repository and follow the installation instructions. Requisites:
- matplotlib 1.5.1: if a newer version is installed in your system, downgrade with
pip install 'matplotlib==1.5.1' --user --force-reinstall
Move the recorded bags to calibration/kalibr, cd there and run:
kalibr_calibrate_cameras --target checker_8x5.yaml --bag back_camera.bag \
--models omni-radtan --topics /cam_1/image_back_raw --show-extraction
kalibr_calibrate_cameras --target checker_8x5.yaml --bag front_camera.bag \
--models omni-radtan --topics /cam_1/image_front_raw --show-extraction
The results are stored in the same folder as:
camchain-back_camera.yamlcamchain-front_camera.yaml
Detailed results are written into the files:
results-cam-back_camera.txtresults-cam-front_camera.txt