Monday, March 28, 2016

Getting started... IMU+camera calibration

To start our computer vision and robotics blog, I'd first like to begin with the topic of camera calibration. 



Now, to be fair, camera calibration is a fairly mature subject with numerous tutorials, blogs and DIY instructions available all over the web and their is hardly any novelty in discussing it here. I'll provide some common links which you might find helpful for simple camera calibration:


  1. http://wiki.ros.org/camera_calibration/Tutorials/MonocularCalibration
  2. http://docs.opencv.org/2.4/doc/tutorials/calib3d/camera_calibration/camera_calibration.html
  3. http://opencv-python-tutroals.readthedocs.org/en/latest/py_tutorials/py_calib3d/py_calibration/py_calibration.html
  4. http://boofcv.org/index.php?title=Tutorial_Camera_Calibration
  5. http://www.vision.caltech.edu/bouguetj/calib_doc/
...there are many other such examples, across various platforms, which essentially does the same thing. Calibrate a monocular camera. The relative accuracy of each of these approaches and their ease of implementation varies from case to case, and that itself might warrant a separate discussion.But that is not what we intend to focus on.

What we will consider here is a slightly tricky scenario of a visual inertial system, which is made up of a camera and an IMU unit, which are coupled together in a single rigid body. If you haven't already figured it out, the most common example of this system is a mobile device. However, quadrotors and wheeled mobile robots with cameras are almost equally popular.

What we are trying to do:


The objective is to calibrate the camera (intrinsics and lens distortion) as well as do a camera to IMU calibration, i.e, estimate the relative pose of camera w.r.t the IMU. We will be using Kalibr toolbox for this.

Why do we do this:

In most mobile devices, you have no idea where the IMU is placed in the phone's body. For robots, you might have some idea, but they are probably quite inaccurate.



Things you need to know before you start:

You need to know and be prepared about the following:

  1. Proper mechanism to log data from you IMU and capture image/video sequence from your camera
  2. You must be prepared to print an APRIL tag on a large sheet of paper, preferably A0 sized
  3. You need to know the angular random walk and noise density of your IMU, which should ideally come from the data sheet of your sensor

How we do this?

This entire concept of IMU+Camera calibration has been taken up from ETH Zurich's research. The project is called Kalibr. The rest of the post will focus on how to get this to work on your bot/mobile.

I have forked this repository at: https://github.com/WildEngineers/kalibr Clone it into your system. We will assume you are using this from a Ubuntu system.
// Clone
 git clone https://github.com/WildEngineers/kalibr.git

Step 1: Multiple Camera Calibration:

  1. First you need to print out a calibration target. The easiest way is to download this APRIL tag and get it printed on an A0 paper. However, the logistics of printing on an A0 paper can be bothersome. We would suggest getting it printed on as large a sheet as possible (you can later specify the dimensions of the APRIL grids). If the APRIL tags are small, calibration will fail. Check this Wiki page for all the options you have regarding calibration targets.
  2. The next thing we need is to collect data. Use your multi-camera setup (or single camera, doesn't matter) to image the calibration target from all possible angles.
  3. For the setup to work ideally (especially for the IMU calibration), you should directly log the image sequence from the imaging device, and the logged images should have their corresponding timestamps in the file name, i.e, each image should be named 'timestamp.png' (Ex: 1284030212179407200.png, 1284030212179409200.png..... etc.) However, if you have captured the sequence as a video file, you need to split it into images (please note, this is a little hacky). If you have FFMPEG configured in your system , you can use the following script:
    ffmpeg -i /path/to/video.mov  -r 30 -f image2 /path/to/ouput/folder/image_%04d.png
    
    (Make sure you set the frame rate correct, under the -r flag). A small tip: if you are using an USB camera, you might try the following script for capturing video:
    ffmpeg -f avfoundation -video_size 544x288 -framerate 30 -i 0 /path/to/output/out.mpg 
    Once you have the image sequence in place, you'll have to rename the files, starting from the first timestamp at which you began recording the video. Each subsequent image will have a timestamp incremented by the amount of delay that is expected between consecutive frames. You might have to write a small script for doing this, should be straightforward.
  4. You'll need to do this for every camera in your setup. Generalizing, for a N camera setup, you will end up with N folders, each containing image sequences of the same calibration target. Name the folders cam0, cam1, cam2.... camN. (However, there's a disclaimer. We haven't really tested it for more than two cameras. Should work, though)
  5. You also need to have a text file, imu0.csv. However, it is not strictly necessary for camera calibration. The data from this file would be put to use when we step into IMU-camera calibration. However, if you intend to simply calibrate your cameras and skip the IMU calibration part, you can just put a blank imu0.csv file in your dataset directory. 
  6. If you do want to continue with IMU calibration, you need to create the imu0.csv cautiously. The format of this file is: 
    timestamp,omega_x,omega_y,omega_z,alpha_x,alpha_y,alpha_z
    It should be logged while you are capturing the video/image sequence of the target. Please note that the number of data points in the imu0.csv file and the number of images in the cam0/cam1 folder wouldn't be equal, since the image sensor and gravity/angular rate sensors operate in different frequencies. This is fine. However, looking at the time stamp, the images and the IMU reading will over lap after certain number of data points (you can easily calculate this number from the frequencies). 
  7. By now, we are done with data collection. We now have to begin with the process of *.bag file creation.
  8. BAG file creation: Basically, we do what is described here. Your dataset folder should look like
    +-- dataset-dir
      +-- cam0
      │ +-- 1385030208726607500.png
      │ +-- ...
      │ \-- 1385030212176607500.png
      +-- cam1
      │ +-- 1385030208726607500.png
      │ +-- ...
      │ \-- 1385030212176607500.png
      \-- imu0.csv
  9. Download this file and extract it. With your dataset directory formatted, run the following script:
    kalibr_bagcreater --folder dataset-dir --output-bag sample.bag
  10. With your dataset bag file created, you can now move on to the actual camera calibration step
  11. Camera Calibration: Before you run camera calibration, you need one more .yaml file, describing the nature and physical dimensions of the calibration target you used. We will describe the details for the APRIL grid. Create a file called grid.yaml and put the following lines in it:
      target_type: 'aprilgrid' #gridtype
      tagCols: 6                  #number of apriltags
      tagRows: 6                  #number of apriltags
      tagSize: 0.088              #size of apriltag, edge to edge [m]
      tagSpacing: 0.3             #ratio of space between tags to tagSize
    All dimension must be in metres. Depending on what size of a printout you opted for in Step 1, you can have different dimensions here. The number of columns and rows would stay unchanged, if you have used the same calibration targets. As for the 'tagSize' and 'tagSpacing' values, take a ruler and measure them out.
  12. Put the dataset .bag file and the target desciptor .yaml file in one folder. You are now ready to run calibration. Fire this:
     kalibr_calibrate_cameras --target grid.yaml --bag sample.bag --models pinhole-radtan --topics /cam0/image_raw
    the '--models' parameter takes multiple values. Check this for all supported models. Unless you are using an omnidirectional camera, 'pinhole-radtan' should mostly work.
  13. That should do. The calibration step will run for a while and produce an output that looks like this:
     Camera-system parameters:
        cam0 (/cam0/image_raw):
         type: (class aslam_cv.libaslam_cv_python.distortedpinholecamerageometry)
         distortion: [ 0.16743531 -0.23612346 -0.00201245  0.00136913] +- [ 0.00641479  0.01472349  0.00114592  0.00101362]
         projection: [ 543.2765292   545.21772621  182.79121416  170.31643122] +- [ 2.35611620  2.84990877  1.17500811   1.39625201]
         reprojection error: [-0.000000, 0.000000] +- [0.333953, 0.320661]

Step 2: IMU - Camera Calibration:


  1. To get the IMU calibration running, you need two extra files: camchain.yaml and imu.yaml. The YAML formats are described here.
  2. The camchain.yaml describes the camera calibration parameters. Our camchain looks like: 
    cam0:
      camera_model: pinhole
      intrinsics: [543.2765292,545.21772621,182.79121416,170.31643122]
      distortion_model: radtan
      distortion_coeffs: [0.16743531,-0.23612346,-0.00201245,0.00136913]
      rostopic: /cam0/image_raw
      resolution: [544, 288] 
  3. The imu.yaml file describes the internal property of the sensors. A sample might look like:
    #Accelerometers
    accelerometer_noise_density: 0.01   #Noise density (continuous-time)
    accelerometer_random_walk:   0.0002 #Bias random walk
    
    #Gyroscopes
    gyroscope_noise_density:     0.005   #Noise density (continuous-time)
    gyroscope_random_walk:       4.0e-06 #Bias random walk
    
    update_rate:                 200.0 #Hz (for discretization of the values above)
  4. You would, most likely, know what the update rate of your IMU is. However, noise density and random walk of your accelerometer and gyroscope is a slightly obscure parameter. The easiest way to find it is to scourge the data sheet of your sensor. Most IMUs would have this data in the data sheet. If they don't, well, determining noise density and random walk of any sensor could be a topic of its own. Google it. Maybe, check this out.
  5. Once you have everything in place, run this:
     kalibr_calibrate_imu_camera --bag sample.bag --cam camchain.yaml --imu imu.yaml --target grid.yaml
  6. The output should look like this:
    Calibration results
    ===================
    Reprojection error squarred (cam0):  mean 0.252602724559, median 0.372500252216, std: 0.577191079923
    Gyro error squarred (imu0):          mean 32.3216634517, median 26.2663953492, std: 332.2769211626
    Accelerometer error squarred (imu0): mean 0.417702276116, median 0.177752343562, std: 0.91786775127
    Transformation (cam0):
    -----------------------
    T_ci:  (imu to cam0): [m]
    [[ 0.92276152  0.13257979 -0.06337171  0.00072067]
     [-0.17257972  0.926726    0.10395627 -0.00121251]
     [ 0.07627232 -0.09565603  0.99726213  0.0000972 ]
     [ 0.          0.          0.          1.        ]]
    T_ic:  (cam0 to imu): [m]
    [[ 0.92276152 -0.17257972  0.07627232 -0.00095391]
     [ 0.13257979  0.926726   -0.09565603  0.00150171]
     [-0.06337171  0.10395627  0.99726213  0.00011795]
     [ 0.          0.          0.          1.        ]]
    timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
    0.0
    Gravity vector in target coords: : [m/s^7]
    [ 0.000493   -9.81       -0.00004761]
    Calibration configuration
    =========================
    cam0
    -----
      Camera model: pinhole
      Focal length: [278.6140376, 272.67142023]
      Principal point: [238.29527238, 318.70385962]
      Distortion model: radtan
      Distortion coefficients: [0.12550226, -0.28521337, -0.00107526, 0.00022208]
      Type: aprilgrid
      Tags: 
        Rows: 6
        Cols: 6
        Size: 0.087 [m]
        Spacing 0.029 [m]
    IMU configuration
    =================
      Update rate: 100.0
      Accelerometer:
        Noise density: 0.01 
        Noise density (discrete): 0.0575296669251 
        Random walk: 0.0001
      Gyroscope:
        Noise density: 0.002
        Noise density (discrete): 0.0887298335621 
        Random walk: 3e-06
    
  7. You should notice two parameters in the output file: T_ci and T_ic. They are the transformation matrix from the camera to the IMU and reverse, respectively.