Skip to content

Calibrating Intel RealSense Cameras

Patrick Geneva edited this page May 24, 2023 · 3 revisions

Intel RealSense D455: A Complete Tutorial and Discussion

This video walks through the process of performing visual-inertial sensor calibration. This calibration is crucial for downstream applications which try to fuse the two sources of information. The video was recorded in a single session from start to finish, so please use the chapters to skip to the sections which are of interest. The sensor used is the Intel Realsense D455 color camera and internal IMU. The key software used is Kalibr and allan_variance_ros.

Youtube Video

Key software we are going to use:

Calibration slides (slide 51):

We are going to be using the calibration from here (d455 realsense)

Multi-camera calibration guide:

How to calibrate the IMU intrinsics? What is the IMU noise model?

Lets use in kalibr to calibrate the IMU and camera jointly:

When collecting data need to avoid degenerate directions (e.g. planar). Excite two axis motion with non-constant accelerations is crucial!

The different IMU intrinsic models are covered in here:

Rehder, Joern, Janosch Nikolic, Thomas Schneider, Timo Hinzmann, and Roland Siegwart. "Extending kalibr: Calibrating the extrinsics of multiple IMUs and of individual axes." In 2016 IEEE International Conference on Robotics and Automation (ICRA), pp. 4304-4311. IEEE, 2016. https://timohinzmann.com/publications/icra_2016_rehder.pdf

How to interpret results?

  • https://docs.openvins.com/gs-calibration.html
  • Inspect the IMU time dt plot carefully in the PDF report!
  • Your accelerometer and gyroscope errors are within their 3-sigma bounds (if not then your IMU noise or the dataset are incorrect)
  • Ensure that your estimated biases do not leave your 3-sigma bounds. If they do leave then your trajectory was too dynamic, or your noise values are not good.
  • Sanity check your final rotation and translation with hand-measured values.

Example of bad IMU timestamps where a burst of IMU are send at a rate of 1ms with gaps of 6ms between (caused by sending messages in buffers and directly republishing them).

Intel RealSense T265: Live OpenVINS State Estimation Demo

In this video takes from having a sensor, to collecting data, performing calibration, and finally processing that data live with OpenVINS to recover a 6dof pose estimate. First we create a launch file for the Intel Realsense T265 sensor, after which we perform calibration. Finally we use the calibration to process data with OpenVINS and demo the recovered trajectory.

Youtube Video

Key software needed to have built in your ROS workspace

Ensure you have realsense driver installed:

sudo apt install ros-noetic-realsense2-camera
sudo apt-get install librealsense2-udev-rules
sudo apt-get install librealsense2-utils

Check that you can see your sensor with the following

rs-enumerate-devices

Launch for realsense driver (examples seem to be on ros1-legacy). Need to ensure unite_imu_method is linear_interpolation!

Calibration with pinhole-equi camera model and scale-misalignment

How to get good calibration?

  • Limit motion blur by decreasing exposure time
  • Publish at high-ish framerate (20-30hz)
  • Publish your inertial reading at a reasonable rate (200-500hz)

The different IMU intrinsic model are described in:

Rehder, Joern, Janosch Nikolic, Thomas Schneider, Timo Hinzmann, and Roland Siegwart. "Extending kalibr: Calibrating the extrinsics of multiple IMUs and of individual axes." In 2016 IEEE International Conference on Robotics and Automation (ICRA), pp. 4304-4311. IEEE, 2016. https://timohinzmann.com/publications/icra_2016_rehder.pdf

How to run this with OpenVINS with live data?

Need to create configuration file:

  • Need the IMU noises and intrinsics
  • Copy over the camera intrinsics and calibration

Now we can run the following commands:

rviz -d ./src/open_vins/ov_msckf/launch/display.rviz
roslauch ov_msckf subscribe.launch config:=path_estimator.yaml