WARNING: Recent testing of the rail calibration procedure indicate that the procedure described in this tutorial will only yield good results if the camera moves along its optical axis. Care should therefore be taken to aim your camera such that the center pixel is exactly aligned with the same target feature both a the front and the back. An alternate procedure with an alternate cost-function has been developed that does not require accurate aiming of the camera. It does, however, require two sets of images be taken. Both sets of images have the camera moving along the same axis in camera coordinates, but a different axis relative to the target. This axis of motion is estimated along with the two starting poses of the camera along the rail.

(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Intrinsic Camera Calibration

Description: This tutorial shows how to use the intrinsic camera calibration package to compute the camera intrinsic parameters using a rail guide and calibration target. The procedure uses a slightly different cost function than OpenCV and Matlab. It relies on knowing the distance the camera is moved between successive images. When performed precisely, the routine is both quicker because it requires fewer images and more accurate because the parameters have lower co-variance.

Tutorial Level: INTERMEDIATE

Requirements

  1. ASUS PrimeSense camera

  2. Linear guide rail
  3. Calibration target
    • When choosing a calibration target, keep in mind that we are using openCV's findCirclesGrid() routine. More cirlces means more measurements and therefore better results. However they can't be too small, or findCirclesGrid() won't find them at the far end of the rail.
  4. Incandescent lamp or other IR light source

Setup

  1. Place calibration target on a flat wall
  2. Setup calibration rail in front of the calibration target and ensure that the rail moves the camera back and forth along the z-axis of the camera.
  3. Make sure that calibration target fills the field of view when camera is at the front most position.
    1. Measure distance from the wall to the camera stand when it is at the front most position on the rail.

      distance from target to first position

  4. Run the program: roslaunch intrinsic_calibration rail_ical_asus.launch. Slide camera to back position. Make sure that center pixel of image points at the same location in both the near and far locations. This ensures that the camera is pointing in the direction of travel of the rail. Adjust the camera pitch and yaw until the center pixel is the same, or very close, for both locations. This can be done by using the red circle drawn in the center of the image. Make sure that the pixel that shows up inside this circle is close to the same (within 1-5 pixels distance) in the near and far locations.
    alignment image at a point close to the target alignment image at a point far from the target

  5. Modify the launch file “rail_ical_asus.launch” to include the following (all lengths in are meters):
    1. The size of the calibration grid used (rows, columns, circle diameter, circle spacing)
      • Rows/columns are determined based upon the location of the origin circle, which is located in the bottom left corner of the target.
    2. The distance of the camera from the calibration target when in the nearest location (measured in Step 2ii). This provides an initial condition for the one exterior pose estimated during calibration.
    3. The distance the camera moves at each increment
    4. The number of times the camera will be moved and a new image acquired (Should not exceed the travel of the rail)

Procedure

  1. roslaunch intrinsic_calibration rail_ical_asus.launch

  2. Call service to start the process
    1. rosservice call /RailCalService “allowable_cost_per_observation: 0.0”

    2. Set the cost per observation to a reasonable number. If the position measurement accuracy is within 1mm for each position, then the error is typically less than 1 pixel for each circle observed. If there is side to side wobble in your setup, you may observe more residual error. It should never be more than a few pixels.
  3. Move rail to the first/closest position where the target fills the field of view completely.
    1. Accuracy of rail placement affects the intrinsic calibration results. Be sure to measure accurately or use hard stops to ensure that the calibration is reliable.
  4. To capture each calibration image, set the ROS parameter “/rail_intrinsic_calibration/camera_ready” to true
    1. rosparam set /rail_intrinsic_calibration/camera_ready true
    2. Verify that the target was found correctly. All circles should have a white dot in the center, the origin circle should have a larger dot, and the top row should be connected with a white line.

      target observer results

  5. Move the rail to the next position as prompted in the terminal. Set the "camera_ready" parameter to true and repeat until all positions are completed.
  6. If the target was not found in any of the positions, resolve any issues and rerun the program. Depending on the size of your circle grid, there will be an upper limit on the distance away at which the target can be seen and identified. Possible causes of failure may include:
    1. Not enough contrast between circles and background, increase color contrast or lighting. Remove any glare that may exist on the target
    2. Improper circle spacing/sizing resulting in failed detections at far away distances. Make sure that distance between circles (especially the origin circle) is large enough that they can be distinguished in the image at all distances.
    3. Circles not being found at the edge of the field of view if the camera is too close to the target
  7. Repeat procedure for the IR camera
    1. roslaunch intrinsic_calibration rail_ical_asus.launch ir:=true

    2. Use an IR light source (incandescent light bulb) and cover up the IR projector or use a diffusor on the IR projector (can result in uneven lighting on target, too bright up close and too dim far away)
    3. Repeat steps 3-5
    4. Note that the results are stored by the camera's camera_info_manager

Validation

After calibration has been performed the results can be checked to see if they are accurate by calling the /TargetLocatorService and give reasonably close numbers for the target pose.

rosservice call /TargetLocateService "allowable_cost_per_observation: 1.0
roi: {x_offset: 0, y_offset: 0, height: 480, width: 640, do_rectify: false}
initial_pose:
  position: {x: 0.0, y: 0.0, z: 0.5}
  orientation: {x: 1.0, y: 0.0, z: 0.0, w: 0.0}"
  1. Move the camera to the front most position on the rail. Call the /TargetLocatorService and record the result for the z position.

  2. Move the camera to the back position on the rail call the /TargetLocatorService again, and record the new z position.

  3. Compare the results between the measured (actual) and calculated distances.

Results for the camera used in this tutorial can be seen in the table below (f=538).

ground truth

intrinsic calibration results

1% error in f

2% error in f

measured distance (m)

0.65

0.6501

0.6390

0.6260

distance error (%)

N/A

0.02

1.69

3.69

Wiki: intrinsic_cal/Tutorials/Hand Rail Calibration (last edited 2018-07-30 20:58:00 by DrChrisLewis)