• DepthAI-v2
  • OAK-D-PRO different undistort results between stereoDepth and cv2.undistort

Hello !

I get very different "undistorted" images when I get the recified output of the stereoDepth node as compared to when I try to undistort the image using opencv's undistort, with the intrinsic matrix and distortion coefficients coming from the device.

FYI the depth seems to be working fine (I recalibrated our oak)

Here is a minimal working example

import cv2
import depthai as dai
import numpy as np

pipeline = dai.Pipeline()

left = pipeline.createMonoCamera()
left.setBoardSocket(dai.CameraBoardSocket.CAM_B)
left.setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P)

right = pipeline.createMonoCamera()
right.setBoardSocket(dai.CameraBoardSocket.CAM_C)
right.setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P)

xout_left = pipeline.createXLinkOut()
xout_left.setStreamName("left")
left.out.link(xout_left.input)

xout_right = pipeline.createXLinkOut()
xout_right.setStreamName("right")
right.out.link(xout_right.input)

depth = pipeline.createStereoDepth()
depth.setLeftRightCheck(True)
depth.setExtendedDisparity(False)
depth.setSubpixel(True)
depth.setDepthAlign(dai.CameraBoardSocket.CAM_B)
left.out.link(depth.left)
right.out.link(depth.right)

xout_depth = pipeline.createXLinkOut()
xout_depth.setStreamName("depth")

depth.depth.link(xout_depth.input)

xout_rect_left = pipeline.createXLinkOut()
xout_rect_left.setStreamName("rect_left")
depth.rectifiedLeft.link(xout_rect_left.input)

device = dai.Device(pipeline)

queues = {}
for name in ["left", "right", "depth", "rect_left"]:
    queues[name] = device.getOutputQueue(name, maxSize=1, blocking=False)

calib = device.readCalibration()
K_left = np.array(calib.getCameraIntrinsics(dai.CameraBoardSocket.CAM_B))
D_left = np.array(calib.getDistortionCoefficients(dai.CameraBoardSocket.CAM_C))

while True:
    left = queues["left"].get().getCvFrame()
    rect_left = queues["rect_left"].get().getCvFrame()
    right = queues["right"].get().getCvFrame()
    depth = queues["depth"].get().getFrame()

    u_left = cv2.undistort(left, K_left, D_left)

    cv2.imshow("left", left)
    cv2.imshow("rect_left", rect_left)
    cv2.imshow("u_left", u_left)
    cv2.imshow("right", right)
    cv2.imshow("depth", depth)

    cv2.waitKey(1)

Am I missing something ?

Thanks !

    I tried tu use cv2.undistort() with the calibration results from oliver-batchelor/multical

    The intrinsics matrices are very close, but the distortion coefficients are very different.

    (On the left, the output of stereodepth.rectifiedLeft, using calibration parameters stored on the device. On the right, cv2.undistort() using calibration parameters from multical)

    apirrone I get very different "undistorted" images when I get the recified output of the stereoDepth node as compared to when I try to undistort the image using opencv's undistort, with the intrinsic matrix and distortion coefficients coming from the device.

    This is likely due to the fact you are only undistorting the images, while the rectification process on the OAKs, both undistorts the images and also rectifies them for stereo matching.

    Though running your example, I got a very similar result.

    Thanks,
    Jaka

    5 days later

    Hi @jakaskerl, thanks for the insight !

    I need to be able to stereo rectify the color stereo pair, I would like to have the same output as the stereoDepth rectified streams, but in color 🙂

    FYI I have two different setups with two FFC-4Ps:

    • Two OV9282 monochrome cameras (wide)
    • Two IMX296 with fisheye lenses

    Trying to replicate the output of the stereoDepth rectified streams, I modified the get_mesh() function given here

    def get_mesh(cam_name, resolution, fisheye, name_to_socket):
        left_socket = get_socket_from_name("left", name_to_socket)
        right_socket = get_socket_from_name("right", name_to_socket)
    
        calib = dai.Device().readCalibration()
        left_K = np.array(
            calib.getCameraIntrinsics(left_socket, resolution[0], resolution[1])
        )
        left_D = np.array(calib.getDistortionCoefficients(left_socket))
        # R1 = np.array(calib.getStereoLeftRectificationRotation())
    
        right_K = np.array(
            calib.getCameraIntrinsics(right_socket, resolution[0], resolution[1])
        )
        right_D = np.array(calib.getDistortionCoefficients(right_socket))
        # R2 = np.array(calib.getStereoRightRectificationRotation())
    
        extrinsics = np.array(calib.getCameraExtrinsics(left_socket, right_socket))
    
        if fisheye:
            R1, R2, P1, P2, Q = cv2.fisheye.stereoRectify(
                left_K,
                left_D,
                right_K,
                right_D,
                resolution,
                extrinsics[:3, :3],
                extrinsics[:3, 3],
                flags=0,
            )
    
            mapXL, mapYL = cv2.fisheye.initUndistortRectifyMap(
                left_K, left_D, R1, P1, resolution, cv2.CV_32FC1
            )
            mapXR, mapYR = cv2.fisheye.initUndistortRectifyMap(
                right_K, right_D, R2, P2, resolution, cv2.CV_32FC1
            )
        else:
            R1, R2, P1, P2, Q, _, _ = cv2.stereoRectify(
                left_K,
                left_D,
                right_K,
                right_D,
                resolution,
                extrinsics[:3, :3],
                extrinsics[:3, 3],
                flags=0,
            )
    
            mapXL, mapYL = cv2.initUndistortRectifyMap(
                left_K, left_D, R1, P1, resolution, cv2.CV_32FC1
            )
            mapXR, mapYR = cv2.initUndistortRectifyMap(
                right_K, right_D, R2, P2, resolution, cv2.CV_32FC1
            )
    
        mapX = mapXL if cam_name == "left" else mapXR
        mapY = mapYL if cam_name == "left" else mapYR
    
        meshCellSize = 16
        mesh0 = []
        # Creates subsampled mesh which will be loaded on to device to undistort the image
        for y in range(mapX.shape[0] + 1):  # iterating over height of the image
            if y % meshCellSize == 0:
                rowLeft = []
                for x in range(mapX.shape[1]):  # iterating over width of the image
                    if x % meshCellSize == 0:
                        if y == mapX.shape[0] and x == mapX.shape[1]:
                            rowLeft.append(mapX[y - 1, x - 1])
                            rowLeft.append(mapY[y - 1, x - 1])
                        elif y == mapX.shape[0]:
                            rowLeft.append(mapX[y - 1, x])
                            rowLeft.append(mapY[y - 1, x])
                        elif x == mapX.shape[1]:
                            rowLeft.append(mapX[y, x - 1])
                            rowLeft.append(mapY[y, x - 1])
                        else:
                            rowLeft.append(mapX[y, x])
                            rowLeft.append(mapY[y, x])
                if (mapX.shape[1] % meshCellSize) % 2 != 0:
                    rowLeft.append(0)
                    rowLeft.append(0)
    
                mesh0.append(rowLeft)
    
        mesh0 = np.array(mesh0)
        meshWidth = mesh0.shape[1] // 2
        meshHeight = mesh0.shape[0]
        mesh0.resize(meshWidth * meshHeight, 2)
    
        mesh = list(map(tuple, mesh0))
    
        return mesh, meshWidth, meshHeight

    I think I am on the right track, as on the OV9282 setup I get very close results:

    From stereoDepth node

    With get_mesh()

    You can see the image is a little bit more zoomed in coming out of the stereoDepth node, and the epilines scores are better (0.03% vs 0.1%)

    This would be acceptable to me.

    However, when checking the same things with the IMX296 color cameras with fisheye lenses, I get:

    From stereoDepth node:

    From get_mesh()

    As you can see, both images are weirdly translated, and have large distortion, especially the image on the right.

    The two setups have been calibrated with the same procedure, but they differ in two ways

    • The IMX296 sensors output a 1440x1080 image that I resize to (1280, 800) using an ImageManip node, while the OV9282 are natively (1280,800)

        def create_manipRescale(pipeline, resolution):
            manipRescale = pipeline.createImageManip()
            manipRescale.initialConfig.setResize(resolution[0], resolution[1])
            manipRescale.setMaxOutputFrameSize(resolution[0] * resolution[1] * 3)
            return manipRescale
    • The lenses mounted on the IMX296 have a larger FOV than the OV9282W (below examples without undistort)

    A few other questions while I am at it:

    • Can https://docs.luxonis.com/projects/api/en/latest/samples/Camera/camera_undistort/#undistort-camera-stream be used to do what I want to do ? Is it mature or still experimental ? Right now I get black images with the IMX296 sensors when trying to get any output (video, preview, isp) from this node
    • Would it be possible to directly get the meshes computed by the stereoDepth node ? It would be perfect, as I would just need to instantiate a StereoDepth node, get the mesh and set it as the warp mesh of my rectify ImageManip node.

    Sorry, that's a lot, thanks for your time!

    Antoine

      Hi apirrone

      apirrone The IMX296 sensors output a 1440x1080 image that I resize to (1280, 800) using an ImageManip node, while the OV9282 are natively (1280,800)

      These aspect ratios are not the same, which means the image will get cropped. In that case you need to change the intrinsics, distortion and extrinsics to reflect that change.

      apirrone Can https://docs.luxonis.com/projects/api/en/latest/samples/Camera/camera_undistort/#undistort-camera-stream be used to do what I want to do ? Is it mature or still experimental ? Right now I get black images with the IMX296 sensors when trying to get any output (video, preview, isp) from this node

      The node is very experimental. Make sure you are running the latest depthai version.

      apirrone Would it be possible to directly get the meshes computed by the stereoDepth node ? It would be perfect, as I would just need to instantiate a StereoDepth node, get the mesh and set it as the warp mesh of my rectify ImageManip node

      I think the device just uses the calibration parameter that we acquire through the calibration process. Same ones you used above and here.

      Thanks,
      Jaka

      @jakaskerl I think the device just uses the calibration parameter that we acquire through the calibration process. Same ones you used above and here.

      Is the code that computes the mesh in the node available ? I could not find it

      @jakaskerl These aspect ratios are not the same, which means the image will get cropped. In that case you need to change the intrinsics, distortion and extrinsics to reflect that change.

      Isn't that what passing the width and height to calib.getCameraIntrinsics(left_socket, width, height) does ?

      Strangely, I was finally able to get a result very close to the rectified streams of stereoDepth with the IMX296 by using cv2.stereoRectify()` instead of cv2.fisheye.stereoRectify(), while the calibration parameters have been computed with cv2.fisheye.stereoCalibrate() and I must use cv2.fisheye.initUndistortRectifyMap() . Any idea of what's going on ?

      StereoDepth rectified

      get_mesh() with cv2.stereoRectify() instead of cv2.fisheye.stereoRectify()