(!) 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.

RGBD depth correction: version 1 (work in progress)

Description: This tutorial shows how to use the depth calibration procedure to correct a point cloud from an ASUS PrimeSense sensor.

Tutorial Level: INTERMEDIATE

Requirements

  1. ASUS PrimeSense camera

  2. Linear guide rail
  3. Large, flat wall
  4. Calibration target
    • When choosing a calibration target, keep in mind that the target must be able to be seen by the camera at all distances over which you are calibrating. Check the closest and furthest point to ensure that the target is visible and found by the industrial_extrinsic_cal target_finder node.

Setup

This assumes that the surface the target is on is flat and featureless. If the surface is not flat, then any artifacts will be saved in the depth correction map, and cause incorrect results when the sensor is moved to a different location.

target and rail setup

Choose a working range over which you will calibrate and operate the camera. Make sure to take images over the whole working range. If the camera is operated outside of the range that it is calibrated in, then the extrapolated depth correction may not perform well.

  1. Set the camera on the rail at the close location, verify that the target can be found
    1. call the target finder service and provide reasonable values for the position and orientation of the target (within 0.5m and +/- 30 degrees is sufficient)
      • 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: 1.0}
          orientation: {x: 0.707, y: 0.0, z: 0.0, w: 0.707}"
    2. verify that the target is found
  2. Move camera to the back location, verify that the target can be found

Procedure

  1. Modify the launch file 'calibrate.launch' to include the parameters for the target that you are using
    • rows/columns
    • diameter/spacing
  2. roslaunch rgbd_depth_correction calibrate.launch

  3. Set the camera at the back most location
  4. rosservice call /pixel_depth_correction

  5. Move the camera to a series of positions and collect the image
    • move camera to new position (~10 positions in total, evenly distributed across the full calibration range)
    • rosservice call /store_cloud

  6. After all images have been collected rosservice call /depth_calibration

    • This step may take some time to solve for the depth correction terms.

Validation

  1. Modify the correction.launch file to match the target size you are using
    • rows, columns, size, spacing for the extrinsic calibration node
    • TF frame locations. The (x,y) location should correspond to the corners of your target where the origin is located in the center of the largest circle
    • Set camera_info_urls to the pathway that your calibration files are saved if a different location was provided in the calibration step.
  2. roslaunch rgbd_depth_correction correction.launch

  3. rosservice call /calibration_service "allowable_cost_per_observation: 1.0"

  4. Visualize the corrected point cloud and verify that the target TF frames align with the centers of the circles you provided. Insert a grid located at the target origin and use it to compare the flatness of the point cloud. For comparison, switch between the corrected cloud and the uncorrected. Move the camera to several positions and run the calibration service each time. Check to make sure that the point cloud looks correct at each location.

TF frames in center of corner circles Corrected point cloud after calibration

Wiki: rgbd_depth_correction/Tutorials/Depth Correction Version 1 (last edited 2016-01-26 16:12:33 by AlexGoins)