Camera Calibration

Learn how to calibrate cameras.
Ysobel Sims GitHub avatar
Updated 31 July 2023

Camera calibration determines optimal parameters for the cameras. These parameters include the focal length and the transform from one camera to the other. More on the parameters being optimised for camera calibration can be found on the input page.

The calibration requires two steps, creating the nbs recording and using it to find the camera parameters.

Get the Data

  1. Change test/camera.role to include support::logging::DataLogging

  2. Build using ./b build and then install onto a robot using ./b install n<number>. More on building can be found on the Getting Started page or the Build System page.

  3. On the robot, enable compressed image recording in config/DataLogging.yaml. Do this by setting message.output.CompressedImage to true.

  4. Ensure the Left and Right camera serial numbers are correct in their respective configuration files (Left.yaml and Right.yaml).

    The serial numbers can be retrieved by first running lsusb and finding the bus and device numbers for the FLIR/Point Grey cameras. Then run lsusb -s <bus number>:<device number> -v to find the serial numbers.

    Next you need to figure out which serial number is left and which is right. Change the serial number for one camera to an incorrect number (this ensures it's not found when running test/camera). Enable message.output.CompressedImage in NetworkForwarder.yaml. Run ./test/camera and test which camera is working by covering one camera and seeing the resulting image in the NUsight vision tab. Alternatively, you could unplug one camera rather than change the serial number. If the serial number is on the wrong camera configuration file, switch them.

  5. Check the focus of the lenses using the NUsight vision tab. If it is not sharp, focus the camera. This involves pulling the camera out from the head, still plugged in, and loosening the three grub screws. Twist until the camera is focused.

  6. Check the transformation matrix from the left camera to the pitch motor (Hpc) is correct in the Left.yaml file. This should be the transformation matrix from the camera to the end of the rigid body, i.e. the pitch motor as used in forward kinematics. Currently this is 69.952mm in xx, 33.795mm in yy, 64.88mm in zz, and a positive yy-axis rotation of 22^\circ. In SI units the matrix is

    Hpc=[cos(2π180)0sin(2π180)0.0699520100.033795sin(2π180)0cos(2π180)0.064880001]\text{Hpc} = \begin{bmatrix} \cos(\frac{2 \pi}{180}) & 0 & \sin(\frac{2 \pi}{180}) & 0.069952 \\ 0 & 1 & 0 & 0.033795 \\ -\sin(\frac{2 \pi}{180}) & 0 & \cos(\frac{2 \pi}{180}) & 0.06488 \\ 0 & 0 & 0 & 1 \end{bmatrix}
  7. Run ./test/camera on the robot and hold up a board as shown in the below image. There is an appropriate board in the NUbots laboratory. Move the board around to cover the robot's view over time, taking into account that the lenses have a 180180^{\circ} field of view. Move the board around at different distances and angles.

    A white board with black circles in rows.
    Asymmetric circles grid used for calibration.
    A person holding a board in the middle of the photo
    A person holding a board at the bottom of the photo
    A person holding a board to the left
    A person holding a board to the right
    Photos from the robot's cameras of a person moving around a board for camera calibration.
  8. Stop the binary and copy the nbs file created into the NUbots directory on your computer.

    1. To stop the program running, hit Ctrl + c.

    2. Discover the name of the log file created. The file is in the log/test/camera/ folder on the robot. The name corresponds to the date and time it was created, according to the robot. Run ls log/test/camera/ to list all logs.

    3. (optional) Rename the log file, making it easier to copy across to the computer. Change the name with the command mv <old path> <new path>.

    4. Run the command scp <robot address>:<file path> . from the NUbots directory on your computer, not on the robot.

    5. The robot can be turned off at this point. The recording you just made should be on your computer in the NUbots directory. Check that it is before continuing to the next section.

Run the Optimisation

  1. Run the following commands to install the dependencies of the camera calibration tool if you have not done this before

    sudo apt update
    sudo apt install protobuf-compiler libprotobuf-dev
    sudo -H pip3 install --upgrade pip
    sudo -H pip3 install tensorflow opencv-contrib-python ruamel.yaml
  2. Calibrate the cameras by running

    ./b nbs calibrate_cameras <nbs file name> -c <camera config folder>

    <nbs file name> is the name of the nbs file you just created. <camera config folder> is the path to the folder with the two camera config files Left.yaml and Right.yaml. These exist in ./module/input/Camera/data/config/<robot name>/Cameras/.

    The calibration routine changes the values in the camera configuration files.

  3. Verify these values by running vision and checking the output in NUsight.

    1. Ensure NetworkForwarder.yaml has enabled compressed images (message.output.CompressedImage) and vision objects.
    2. Stand the robot up with ./scriptrunner Stand.yaml
    3. Face the robot towards a straight horizontal line, such as a line of bricks on a brick wall.
    4. Run ./test/visualmesh and switch to the vision tab in NUsight

    NUsight should show a blue horizontal line, drawn at a constant height along the wall. If this is the case, then the calibration is verified.

  4. Repeat this process with other robots if needed.

  5. Commit these changes in a new branch on GitHub and make a Pull Request. Read the Git guide if you are unsure about this step.

NUbots acknowledges the traditional custodians of the lands within our footprint areas: Awabakal, Darkinjung, Biripai, Worimi, Wonnarua, and Eora Nations. We acknowledge that our laboratory is situated on unceded Pambalong land. We pay respect to the wisdom of our Elders past and present.
Copyright © 2023 NUbots - CC-BY-4.0
Deploys by Netlify