depthai-core icon indicating copy to clipboard operation
depthai-core copied to clipboard

StereoDepth node uses "spec" values not calibration values -- unexpected and significant depth differences

Open diablodale opened this issue 3 years ago • 12 comments

From what I can discern, the StereoDepth node does not use the calibration data stored on the device. It instead uses spec values. This is unexpected since the factory did a device-specific calibration. And the user may have done their own calibration. Yet StereoDepth does not use these calibrated values.

Setup

  • Microsoft Windows [Version 10.0.19044.1469]
  • VS2019 v16.11.9
  • depthai-core main

Repro

Discovered while writing my app and comparing depth values calculated by StereoDepth on device -vs- by disparity on host.

// setup
monos.setResolution(THE_400_P)
stereoDepth->setSubpixel(true);
stereoDepth->setExtendedDisparity(false);
stereoDepth->initialConfig.setConfidenceThreshold(255);
stereoDepth->initialConfig.setLeftRightCheck(false);
// then setup xouts for both stereoDepth.disparity and stereoDepth.depth

// Data direct from EEPROM calibration on my OAK-D
const float baseline_mm = 10.0f * std::get<dai::CalibrationHandler>(calibration).getBaselineDistance(dai::CameraBoardSocket::RIGHT, dai::CameraBoardSocket::LEFT, false);
// baseline_mm = 73.0895758
const float focalX = std::get<dai::CalibrationHandler>(calibration).getCameraIntrinsics(dai::CameraBoardSocket::RIGHT, disparity.cols, disparity.rows)[0][0];
// focalX = 428.242584

// Data by spec
const auto baselinespec_mm = 10.0f * std::get<dai::CalibrationHandler>(calibration).getBaselineDistance();
// baselinespec_mm = 75.0
const auto fovspec = std::get<dai::CalibrationHandler>(calibration).getFov(dai::CameraBoardSocket::RIGHT, true);
// fovspec = 71.86
const float focalCalc = disparity.cols / (2.0f * std::tanf(DEGREES_TO_RADIANS(fovspec / 2.0f)));
// focalCalc = 441.575653

// my OAK-D, fixed position, therefore has fixed disparity and depth at specific pixel. Values from same seqNum are...
uint16_t subpixel_disparity = 170;  // value direct from stereoDepth.disparity feed at pixel 200, 320
uint16_t depth = 1559; // value direct from stereoDepth.depth feed at pixel 200, 320

Result

Do host-side math on subpixel_disparity to generate a depth in mm. It exactly matches the StereoDepth calculated value only if spec values are used. This is 8.6cm delta from calibrated result.

// spec_depth = 1558.502
float spec_depth = 75.0 * 441.575653 * 8.0 / 170

// calibration_depth = 1472.944
float calibration_depth = 73.0895758 * 428.242584 * 8.0 / 170

Expected

By default, I expect StereoDepth to use the calibrated values stored in the EEPROM. Optionally, to have an API StereoDepth::setDepthBySpec(bool) which enables use of spec values instead.

Workaround

Do depth on the host.

diablodale avatar Jan 30 '22 16:01 diablodale

I think it's just purely because the baseline derived from calibration is nearly always less accurate than mechanics tolerances of the mechanically-assembled baseline. So my understanding is the spec is a more accurate representation of the stereo baseline than what calibration can estimate.

Which to my understanding is often the case… camera intrinsics and rotational extrinsics are very accurate from calibration - but translational extrinsics are nearly always less accurate than can be had from mechanics assembly.

But will confirm with team.

Luxonis-Brandon avatar Jan 30 '22 17:01 Luxonis-Brandon

Yes, that's the case. Baseline is known at "PCB build time". About focal length, you can enforce on latest develop, using setFocalLengthFromCalibration @diablodale By default it's taken from calibration only for fisheye lenses.

SzabolcsGergely avatar Jan 30 '22 17:01 SzabolcsGergely

Got it. Three suggestions:

  1. The new api setFocalLengthFromCalibration(bool) does not have the capability to set the underlying AUTO option...which I assume is nullopt. Clarification in the docs "set AUTO by not setting" or api change to support setting it to AUTO is helpful.
  2. If the spec is better for translation, then should getCameraExtrinsics(), getImuToCameraExtrinsics(), and getCameraToImuExtrinsics() all change their default? All of them default to useSpecTranslation = false. This seem opposite of what I understand from above.
  3. If the calibrated intrinsics are more accurate, then why not use focallength_x (top left of intrinsics matrix) for AUTO?

diablodale avatar Jan 30 '22 17:01 diablodale

  1. you are right. Will change that.
  2. If the user who overwrites the calibration doesn't do a good job in calibrating the device it might lead to depth with is way off. to avoid this I think it is best to use it from the specs unless needed.

saching13 avatar Jan 30 '22 18:01 saching13

  1. That seems a "catch-22" 😂 or inconsistency in Luxonis team viewpoint or philosophy.

🤔 I suspect the majority of customers will have factory calibration. @Luxonis-Brandon writes "camera intrinsics and rotational extrinsics are very accurate from calibration" OAK devices without factory calibration are rare. Customers that overwrite factory calibration with custom calibration are a minority.

Therefore.... If you believe in your factory's calibration -and- the majority of customers have factory calibration ...then the majority of customers will benefit from using that factory calibration.

Using spec for setFocalLengthFromCalibration(AUTO) only helps the minority of customers that write their own calibration and a further subset of those customers that do it poorly. Yes, it is real group of customers, but it is a subset of a minority. Not the majority of customers.

Customers "in-the-know" can force apis to do the right thing. But the majority of your customers will not benefit from your factory calibration. Is that a good approach? It is completely your team's choice.

diablodale avatar Jan 30 '22 19:01 diablodale

Had to ask internally. So we also got feedback from customers that factory data on focal length - for narrow FOV - was actually more accurate than calculated/derived. So that's why we switched to it.

We'll need to do actual testing of depth accuracy for each, and which focal length is closer to actual to see about making a switch.

Luxonis-Brandon avatar Feb 01 '22 05:02 Luxonis-Brandon

Ack. 😵 I've read that 3 times and I still can't sort it. Need to do some testing. Got it.

Until the testing is done I'm attempting to understand what is known or likely known. @Luxonis-Brandon you write "why we swiched to it". What is "it"? From the sentence before, "it" is factory data on focal length for narrow FOV. That "it" is the factory calibration data in EEPROM. That seems in linguistic conflict with the default NFOV behavior of setFocalLengthFromCalibration()...the default is not using that EEPROM calibration data. How does that align with "switched to it"?

Not arguing, just trying to understand the good info your team is communcating to me. So I can choose right params until some future time testing results are available. ✌

diablodale avatar Feb 01 '22 16:02 diablodale

Sorry. Blame the sleep deprivation. What I was meaning is that for NFOV our customer found that using the focal length from calibration resulted in a bit less accurate depth than from using the focal length from spec - at least from their testing from their calibration. When I initially responded I had forgotten that.

So what we'd need to do is a suite of calibration to see if that is the case for our factory calibration, and do it across our suite of models. To make sure we're not making things worse by blanket going to focal length from calibration.

Conversely, for WFOV (150°DFOV), focal length from calibration is always better than from spec. So we should default use the focal length from calibration in that case.

Luxonis-Brandon avatar Feb 01 '22 18:02 Luxonis-Brandon

That I can grok. 😄 Thank you.

I'll keep this open so to verify the change of cali apis useSpecTranslation = false --> true and the upcoming setFocalLengthFromCalibration(). The remaining I have clarity. 👍

diablodale avatar Feb 01 '22 23:02 diablodale

Thanks sounds good to me and CC: @saching13 for any comment or correction of anything I'm saying here.

Luxonis-Brandon avatar Feb 02 '22 01:02 Luxonis-Brandon

Everything sounds good.

If the user who overwrites the calibration doesn't do a good job in calibrating the device it might lead to depth with is way off. to avoid this I think it is best to use it from the specs unless needed.

@diablodale just a small comment. Our Factory calibration is as accurate as possible with an epipolar error of less than 0.5 for the stereo with a board 3X the size of the one user calibration does. And any calibration routine can be as accurate as the user gets the calibration board and how much variance he adds while capturing images during calibration. And if we already know anything specific like 100% we should use that. Not an estimation (The calibration process is just a least square estimation. There is a good chance that occasionally it gets stuck in local minima).

And Yes. I will update the useSpecTranslation = true by default

saching13 avatar Feb 02 '22 02:02 saching13

😂 like Indy Jones Temple of Doom... the "Cali--maaa" scene. Cali can sometimes hurt 💔💀

diablodale avatar Feb 02 '22 19:02 diablodale