ON THIS PAGE

  • RGB-D
  • Aligning RGB and Depth Images
  • Alignment using DepthAI
  • StereoDepth - for stereo cameras
  • ImageAlign - general alignment
  • RGB-D on Wide FOV cameras
  • Using Camera node
  • Manual undistortion
  • Alpha and maximizing FOV

RGB-D

RGBD refers to the type of image data that includes both color (RGB) and depth (D) information.

Aligning RGB and Depth Images

Core element of RGB-D pipeline is alignment. The idea is to align each pixel in the depth image with the corresponding pixel in the color image. This is necessary because the depth image perspective is different from the color image perspective due to the different camera positions.The alignment can be done using reprojection. By default, the depth is aligned to the rectified_left image during the stereo-matching process. We can project this image to 3D space (using acquired depth information) and then reproject it back to the color image plane using color camera intrinsics.

Alignment using DepthAI

DepthAI provides a few ways to achieve alignment of RGB and depth images which all offer the same functionality, but have their own benefits and drawbacks.

StereoDepth - for stereo cameras

The StereoDepth node offers alignment capabilities out of the box. The node takes in a pair of stereo images (left and right) and outputs a depth map. By default, the depth image is aligned with the rectified_left image, but can be changed using the setDepthAlign() method.
Python
1stereo.setDepthAlign(dai.CameraBoardSocket.RGB) # Provided that the RGB camera is connected to RGB/CAM_A port

ImageAlign - general alignment

The ImageAlign node is a more general-purpose node that can be used to align any two images. The node takes in two images (input and inputAlignTo) and outputs the aligned image. For RGB-D, this node allows us to align the Time-of-Flight (ToF) depth to RGB.

RGB-D on Wide FOV cameras

When using WFOV cameras, the alignment can be tricky due to the large distortion in the images caused by the lens. By default, the depth image is undistorted during the rectification-undistortion process, but the color image is not. This can lead to misalignment between the two images. To solve this, the color image needs to be undistorted as well.
1

Using Camera node

Using Camera node. The node can be used to undistort the color image using the intrinsic parameters of the camera.
Python
C++

Python

Python
1cam = pipeline.create(dai.node.Camera)
2cam.setBoardSocket(dai.CameraBoardSocket.RGB)
3cam.setMeshSource(dai.CameraProperties.WarpMeshSource.CALIBRATION)
2

Manual undistortion

The undistortion can be done manually using the intrinsic parameters of the camera and OpenCV.
Python
1alpha = 0
2stereo.setAlphaScaling(alpha)
3
4rgb_w = camRgb.getResolutionWidth()
5rgb_h = camRgb.getResolutionHeight()
6rgbIntrinsics = np.array(calibData.getCameraIntrinsics(rgbCamSocket, rgb_w, rgb_h))
7rgb_d = np.array(calibData.getDistortionCoefficients(rgbCamSocket))
8rgb_new_cam_matrix, _ = cv2.getOptimalNewCameraMatrix(rgbIntrinsics, rgb_d, (rgb_w, rgb_h), alpha)
9map_x, map_y = cv2.initUndistortRectifyMap(rgbIntrinsics, rgb_d, None, rgb_new_cam_matrix, (rgb_w, rgb_h), cv2.CV_32FC1)
10
11frameRgb = cv2.remap(frameRgb, map_x, map_y, cv2.INTER_LINEAR)

Full code

Example using OpenCV undistortion

3

Alpha and maximizing FOV

When undistorting an image captured by a wide FOV camera, the warping will cause some parts of the image to be cut off. This results in the loss of FOV which is the primary selling point of WFOV cameras. To maximize the FOV, the alpha parameter [0-1] can be used to scale the undistorted image [guide].

Setting alpha parameter

  • alpha = 0 - No scaling, the undistorted image will be the same size as the original image.
  • alpha = 1 - Maximum scaling, the undistorted image will be the largest possible image that fits in the original image.
StereoDepth undistortion
Camera undistortion
OpenCV undistortion

StereoDepth undistortion

Python
1stereo.setAlphaScaling(alpha)

Need assistance?

Head over to Discussion Forum for technical support or any other questions you might have.