Online Marker-free Extrinsic Camera Calibration using Person Keypoint Detections
preview.mp4
This ROS-package provides extrinsic calibration for a static camera network providing person keypoint detections.
We assume the intrinsic calibration and a rough estimate of the extrinsic calibration to be available.
The package was tested with ROS melodic and Ubuntu 18.04, as well as ROS noetic and Ubuntu 20.04.
The former requires the geometry2 and cv_bridge packages to be placed in the catkin_ws/src
folder.
Both packages must be built with Python3 support, e.g. using
catkin_make -DPYTHON_EXECUTABLE:FILEPATH=/usr/bin/python3 -DPYTHON_INCLUDE_DIR=/usr/include/python3.6m -DPYTHON_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.6m.so
The received person keypoint detections must be encoded using the person_msgs package with the default joint order being defined here.
Place the person_msgs
package it in your catkin_ws/src
folder and build it via catkin_make
or catkin_build person_msgs
.
The factor graph optimization is implemented using the GTSAM library,
which can be installed by pip install gtsam==4.1.1
.
For additional standard-dependencies, see calibration.py.
Place the keypoint_camera_calibration
package in your catkin_ws/src
folder.
Navigate to your catkin_ws
and run catkin_make
or catkin_build keypoint_camera_calibration
,
depending on your build system.
The examples folder contains calibration files for the presented camera network.
The initial estimate of the extrinsic calibration gets generated automatically by retracting the reference calibration.
The corresponding calibration and evaluation bagfiles can be found here.
All parameters are preset for this scenario.
Simply start the calibration pipeline by
rosrun keypoint_camera_calibration calibration.py
Play one of the provided bagfiles to start calibration
rosbag play $(rospack find keypoint_camera_calibration)/examples/bagfiles/2022-05-26_calib_2persons_3min.bag
Results will be placed in the logs
folder.
Visualization presets for rqt
and rviz
are provided.
Provide .yaml
files following the syntax established in the example files:
- Intrinsic calibration
- Estimated extrinsic calibration
- Reference extrinsic calibration (optional)
Edit the required parameters in the __init__
function of calibration.py to match your scenario:
- File locations
- Message properties
- Method parameters
Start calibration by
rosrun keypoint_camera_calibration calibration.py
Provide person_msgs
by playing a bagfile or accessing a sensor network.
Bastian Pätzold, Simon Bultmann, and Sven Behnke:
Online Marker-free Extrinsic Camera Calibration using Person Keypoint Detections.
DAGM German Conference on Pattern Recognition (GCPR), Konstanz, September 2022.
This package is licensed under BSD-3.