• Hardware
  • OAK-FFC-P3: Setup with x3 OV9282 Mono Cameras

I'm trying to figure out if it is possible to setup an OAK-FFC-P3 Board with 3 Mono cameras (all three of them are OV9282) instead of 2 mono cameras and an rgb camera.

It seems like following the processes Luxonis Calibration Procedure has been difficult so far. My end goal is to get the following data for each camera:

  • Extrinsic Matrix (assuming 'mono_left' is our world frame)
  • Intrinsic Matrix
  • Distortion Coefficients

Here is the setup I'm working with:
x3 OV9282 Sensors
x1 OAK-FFC-P3

Nominal Geometry:
left Camera to Right camera:
x,y, z: {30.1cm, 0, 0}
yaw, pitch, roll: { 0, 0 ,0}
left Camera to Center Camera:
x, y, z: {14.6cm, -16.2cm ,0}
yaw, pitch, roll: {0, 0, 0}

So far, attempting to follow the Calibration Page linked to above I've had issues related to:

  1. a repeated warning indicating there is no calibration loaded on the device
  2. if CAM_A, CAM_B, AND CAM_C are all of type: "mono" in the custom .json file, I get the following error when running:

CUSTON JSON:

  1. IF i remove CAM_A (i.e. the 3rd MonoCamera) I was still having issues calibrating the two Mono Cameras. I was hoping you could give me some beta on this process.

Cheers,
Kyle

Hi @pkyleUPI
You can set the .json file to include model names for each camera (eg. `"model": "OV9282")

Similar to how it's done here.

{
    "board_config":
    {
        "name": "Custom FFC",
        "revision": "R1M0E1",
        "cameras":{
            "CAM_A": {
                "model": "OV9782",
                "name": "right",
                "hfov": 71.86,
                "type": "color",
                "extrinsics": {
                    "to_cam": "CAM_D",
                    "specTranslation": {
                        "x": 10.95,
                        "y": 0,
                        "z": 0
                    },
                    "rotation":{
                        "r": 0,
                        "p": 0,
                        "y": 0
                    }
                }
            },
            "CAM_D": {
                "model": "OV9782",
                "name": "left",
                "hfov": 71.86,
                "type": "color"
            }
                

        },
        "stereo_config":{
            "left_cam": "CAM_D",
            "right_cam": "CAM_A"
        }
    }
}

Thanks,
Jaka

    jakaskerl
    Despite altering the json file to the following, I'm still getting an error related to the OV9782 Sensor name:

    Do I need to somehow load this to the device before calibration?

    UPDATED to include recommended support data:
    Device Model: OAK-FFC-P3
    Cameras: x3 OV9282
    DepthAI Branch Used: commit hash: f4a0d3d4364565faacf3ce9f131a42b2b951ec1b
    Full Command Used for Calibration:
    python3 calibrate.py -s 2.42 -brd ~/LibConstruction/python_depthAI/depthai/resources/depthai_boards/boards/OAK-FFC-3P-POSE_EST.json -nx 13 -ny 7
    Dataset Folder: N/A (doesn't get to the steps when this is produced)
    Json File from Calibration: (see image above)
    Other Notes: I can get the calibration routine to work if I remove 'CAM_A' from the .json File and run it with just the left and right cameras

    Hi @pkyleUPI
    Right, sorry, please switch to develop branch of depthai to get the new feature.

    Thanks,
    Jaka

    This Allows me to perform the calibration, and write to a .json; however, I get the following error when running calibrate.py:

    Device closed in exception..
    No PROTECTED permissions to override protected EEPROM fields
    Traceback (most recent call last):
    File "calibrate.py", line 1124, in calibrate
    self.device.flashCalibration2(calibration_handler)
    RuntimeError: No PROTECTED permissions to override protected EEPROM fields

    Additionally I've tried using a new OAK-FFC-3P and get a different error:
    Device closed in exception..
    Error flashing calibration to USER area, error: EEPROM_FIELD_TOO_LONG
    Traceback (most recent call last):
    File "calibrate.py", line 1124, in calibrate
    self.device.flashCalibration2(calibration_handler)
    RuntimeError: Error flashing calibration to USER area, error: EEPROM_FIELD_TOO_LONG

    Here is my .json file that is generated during calibration:
    {
    "batchName": "",
    "batchTime": 0,
    "boardConf": "",
    "boardCustom": "",
    "boardName": "OAK-FFC-3P_custom",
    "boardOptions": 0,
    "boardRev": "",
    "cameraData": [
    [
    0,
    {
    "cameraType": 0,
    "distortionCoeff": [
    6.287598609924316,
    0.4551546275615692,
    -0.001982076559215784,
    -0.0015794241335242987,
    -7.137771129608154,
    6.026014804840088,
    1.3014261722564697,
    -7.7890472412109375,
    0.0,
    0.0,
    0.0,
    0.0,
    0.0,
    0.0
    ],
    "extrinsics": {
    "rotationMatrix": [],
    "specTranslation": {
    "x": 0.0,
    "y": 0.0,
    "z": 0.0
    },
    "toCameraSocket": -1,
    "translation": {
    "x": 0.0,
    "y": 0.0,
    "z": 0.0
    }
    },
    "height": 800,
    "intrinsicMatrix": [
    [
    799.8438110351563,
    0.0,
    630.3720092773438
    ],
    [
    0.0,
    800.31982421875,
    409.0275573730469
    ],
    [
    0.0,
    0.0,
    1.0
    ]
    ],
    "lensPosition": 0,
    "specHfovDeg": 71.86000061035156,
    "width": 1280
    }
    ],
    [
    1,
    {
    "cameraType": 0,
    "distortionCoeff": [
    -9.850579261779785,
    95.15809631347656,
    0.0005069727776572108,
    -0.0014365238603204489,
    -53.76544952392578,
    -9.895773887634277,
    94.71113586425781,
    -52.327392578125,
    0.0,
    0.0,
    0.0,
    0.0,
    0.0,
    0.0
    ],
    "extrinsics": {
    "rotationMatrix": [
    [
    0.9991858601570129,
    -0.013052552938461304,
    -0.0381738618016243
    ],
    [
    0.013811911456286907,
    0.9997106194496155,
    0.019696488976478577
    ],
    [
    0.037905722856521606,
    -0.020207708701491356,
    0.9990769624710083
    ]
    ],
    "specTranslation": {
    "x": -14.600000381469727,
    "y": 16.200000762939453,
    "z": 0.0
    },
    "toCameraSocket": 0,
    "translation": {
    "x": 15.585432052612305,
    "y": 16.376426696777344,
    "z": 0.6445443630218506
    }
    },
    "height": 800,
    "intrinsicMatrix": [
    [
    801.5814819335938,
    0.0,
    620.4898071289063
    ],
    [
    0.0,
    801.17822265625,
    407.68109130859375
    ],
    [
    0.0,
    0.0,
    1.0
    ]
    ],
    "lensPosition": 0,
    "specHfovDeg": 71.86000061035156,
    "width": 1280
    }
    ],
    [
    2,
    {
    "cameraType": 0,
    "distortionCoeff": [
    8.550910949707031,
    -1.0071139335632324,
    -0.000772843777667731,
    0.0006901727174408734,
    -15.206538200378418,
    8.21905517578125,
    0.09473978728055954,
    -16.081541061401367,
    0.0,
    0.0,
    0.0,
    0.0,
    0.0,
    0.0
    ],
    "extrinsics": {
    "rotationMatrix": [
    [
    0.9998748898506165,
    0.015682443976402283,
    -0.002064539585262537
    ],
    [
    -0.015676937997341156,
    0.9998735785484314,
    0.0026568302419036627
    ],
    [
    0.0021059440914541483,
    -0.002624132204800844,
    0.9999943375587463
    ]
    ],
    "specTranslation": {
    "x": 30.100000381469727,
    "y": 0.0,
    "z": 0.0
    },
    "toCameraSocket": 1,
    "translation": {
    "x": -30.3264102935791,
    "y": 0.052319593727588654,
    "z": 0.1740928590297699
    }
    },
    "height": 800,
    "intrinsicMatrix": [
    [
    797.2682495117188,
    0.0,
    654.8265991210938
    ],
    [
    0.0,
    797.290283203125,
    401.2959289550781
    ],
    [
    0.0,
    0.0,
    1.0
    ]
    ],
    "lensPosition": 0,
    "specHfovDeg": 71.86000061035156,
    "width": 1280
    }
    ]
    ],
    "hardwareConf": "",
    "imuExtrinsics": {
    "rotationMatrix": [],
    "specTranslation": {
    "x": 0.0,
    "y": 0.0,
    "z": 0.0
    },
    "toCameraSocket": -1,
    "translation": {
    "x": 0.0,
    "y": 0.0,
    "z": 0.0
    }
    },
    "miscellaneousData": [],
    "productName": "",
    "stereoRectificationData": {
    "leftCameraSocket": 1,
    "rectifiedRotationLeft": [
    [
    0.9999820590019226,
    -0.0017251846147701144,
    -0.00574053218588233
    ],
    [
    0.0017177382251247764,
    0.9999976754188538,
    -0.0013018285389989614
    ],
    [
    0.0057427650317549706,
    0.0012919444125145674,
    0.9999826550483704
    ]
    ],
    "rectifiedRotationRight": [
    [
    0.9998719096183777,
    0.013972260057926178,
    -0.007809585891664028
    ],
    [
    -0.013962119817733765,
    0.9999015927314758,
    0.0013514565071091056
    ],
    [
    0.0078277001157403,
    -0.0012422449653968215,
    0.9999685883522034
    ]
    ],
    "rightCameraSocket": 2
    },
    "version": 7
    }