From 5e0f513de5bce881dd7c6c358cee4f7d7904573a Mon Sep 17 00:00:00 2001 From: MaticTonin Date: Tue, 18 Mar 2025 00:18:44 +0100 Subject: [PATCH 1/3] Option for v3 pipeline --- calibrate.py | 62 +++++++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 52 insertions(+), 10 deletions(-) diff --git a/calibrate.py b/calibrate.py index 9d782335d..92f74729a 100755 --- a/calibrate.py +++ b/calibrate.py @@ -166,6 +166,8 @@ def parse_args(): help="Enable the display of polynoms.") parser.add_argument('-dbg', '--debugProcessingMode', default=False, action="store_true", help="Enable processing of images without using the camera.") + parser.add_argument('-v3', '--useDepthaiV3', default=False, action="store_true", + help="Use depthai v3.") options = parser.parse_args() # Set some extra defaults, `-brd` would override them if options.defaultBoard is not None: @@ -462,14 +464,18 @@ def mouse_event_callback(self, event, x, y, flags, param): self.mouseTrigger = True def startPipeline(self): - pipeline = self.create_pipeline() - self.device.startPipeline(pipeline) - - self.camera_queue = {} - for config_cam in self.board_config['cameras']: - cam = self.board_config['cameras'][config_cam] - if cam["name"] not in self.args.disableCamera: - self.camera_queue[cam['name']] = self.device.getOutputQueue(cam['name'], 1, False) + if not self.args.useDepthaiV3: + pipeline = self.create_pipeline() + self.device.startPipeline(pipeline) + self.camera_queue = {} + for config_cam in self.board_config['cameras']: + cam = self.board_config['cameras'][config_cam] + if cam["name"] not in self.args.disableCamera: + self.camera_queue[cam['name']] = self.device.getOutputQueue(cam['name'], 1, False) + else: + pipeline = self.create_pipeline_v3() + pipeline.start() + self.pipeline = pipeline def is_markers_found(self, frame): marker_corners, _, _ = cv2.aruco.detectMarkers( @@ -579,6 +585,39 @@ def create_pipeline(self): return pipeline + def create_pipeline_v3(self): + pipeline = dai.Pipeline(self.device) + self.camera_queue = {} + fps = self.args.framerate + for cam_id in self.board_config['cameras']: + cam_info = self.board_config['cameras'][cam_id] + if cam_info["name"] not in self.args.disableCamera: + if cam_info['type'] == 'mono': + cam_node = pipeline.create(dai.node.Camera).build(stringToCam[cam_id]) + self.camera_queue[cam_info['name']] = cam_node.requestFullResolutionOutput(type=dai.ImgFrame.Type.NV12).createOutputQueue(blocking=False) + sensorName = cam_info['sensorName'] + print(f'Sensor name for {cam_info["name"]} is {sensorName}') + else: + cam_node = pipeline.create(dai.node.Camera).build(stringToCam[cam_id]) + self.camera_queue[cam_info['name']] = cam_node.requestFullResolutionOutput(type=dai.ImgFrame.Type.NV12).createOutputQueue(blocking=False) + if cam_info['sensorName'] == "OV9*82": + cam_node.initialControl.setSharpness(0) + cam_node.initialControl.setLumaDenoise(0) + cam_node.initialControl.setChromaDenoise(4) + + if cam_info['hasAutofocus']: + if self.args.rgbLensPosition: + cam_node.initialControl.setManualFocus(int(self.args.rgbLensPosition[stringToCam[cam_id].name.lower()])) + else: + cam_node.initialControl.setManualFocusRaw(int(130 / 255)) + + controlIn = pipeline.createXLinkIn() + controlIn.setStreamName(cam_info['name'] + '-control') + controlIn.out.link(cam_node.inputControl) + sensorName = cam_info['sensorName'] + print(f'Sensor name for {cam_info["name"]} is {sensorName}') + cam_node.initialControl.setAntiBandingMode(antibandingOpts[self.args.antibanding]) + return pipeline def parse_frame(self, frame, stream_name): if not self.is_markers_found(frame): @@ -724,7 +763,7 @@ def capture_images_sync(self): syncCollector.add_msg(key, frameMsg) color_frame = None - if frameMsg.getType() in [dai.RawImgFrame.Type.RAW8, dai.RawImgFrame.Type.GRAY8] : + if not self.args.useDepthaiV3 and frameMsg.getType() in [dai.RawImgFrame.Type.RAW8, dai.RawImgFrame.Type.GRAY8] : color_frame = cv2.cvtColor(frameMsg.getCvFrame(), cv2.COLOR_GRAY2BGR) else: color_frame = frameMsg.getCvFrame() @@ -1082,7 +1121,10 @@ def calibrate(self): print(f'EEPROM VERSION being flashed is -> {eeepromData.version}') eeepromData.version = 7 print(f'EEPROM VERSION being flashed is -> {eeepromData.version}') - mx_serial_id = self.device.getDeviceInfo().getMxId() + if not self.args.useDepthaiV3: + mx_serial_id = self.device.getDeviceInfo().getMxId() + else: + mx_serial_id = self.device.getDeviceId() date_time_string = datetime.now().strftime("_%m_%d_%y_%H_%M") file_name = mx_serial_id + date_time_string calib_dest_path = dest_path + '/' + file_name + '.json' From 07a1b78c0b7ae00eae43757daf13db604a6e69f6 Mon Sep 17 00:00:00 2001 From: MaticTonin Date: Wed, 5 Nov 2025 12:30:45 +0100 Subject: [PATCH 2/3] Adding sanity check for automated switch between dai versions --- calibrate.py | 12 +++++++++++- requirements.txt | 3 ++- resources/depthai_boards | 2 +- 3 files changed, 14 insertions(+), 3 deletions(-) diff --git a/calibrate.py b/calibrate.py index 92f74729a..79760ebbb 100755 --- a/calibrate.py +++ b/calibrate.py @@ -19,6 +19,8 @@ import depthai as dai import numpy as np import copy +from packaging import version +import sys import depthai_calibration.calibration_utils as calibUtils @@ -353,6 +355,7 @@ class Main: def __init__(self): self.args = parse_args() + self.args.useDepthaiV3 = version.parse(dai.__version__) >= version.parse("3.0.0") self.traceLevel= self.args.traceLevel self.output_scale_factor = self.args.outputScaleFactor self.aruco_dictionary = cv2.aruco.Dictionary_get( @@ -464,7 +467,14 @@ def mouse_event_callback(self, event, x, y, flags, param): self.mouseTrigger = True def startPipeline(self): - if not self.args.useDepthaiV3: + if version.parse(dai.__version__) < version.parse("3.0.0"): + if str(self.device.getDeviceInfo().platform) != "XLinkPlatform.X_LINK_MYRIAD_X": + sys.exit( + f"ERROR: RVC4 device detected, but DepthAI version {dai.__version__} is installed.\n" + "RVC4 is NOT supported on DepthAI 2.x.\n\n" + "Please upgrade to the latest DepthAI:\n" + " pip install depthai --upgrade --force-reinstall\n" + ) pipeline = self.create_pipeline() self.device.startPipeline(pipeline) self.camera_queue = {} diff --git a/requirements.txt b/requirements.txt index 36958554b..59a3f1bc9 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,7 +5,8 @@ opencv-contrib-python==4.5.5.62 # Last successful RPi build, also covers M1 with --extra-index-url https://artifacts.luxonis.com/artifactory/luxonis-depthai-data-local/wheels/ pyqt5>5,<5.15.6 ; platform_machine != "armv6l" and platform_machine != "armv7l" and platform_machine != "aarch64" and platform_machine != "arm64" --extra-index-url https://artifacts.luxonis.com/artifactory/luxonis-python-snapshot-local/ -depthai==2.30.0.0 +depthai +numpy>=1.21.4,<2.0.0 # For RPi Buster (last successful build) and macOS M1 (first build). But allow for higher versions, to support Python3.11 (not available in 1.21.4 yet) Qt.py scipy matplotlib diff --git a/resources/depthai_boards b/resources/depthai_boards index 21b7b3988..cb051ef1b 160000 --- a/resources/depthai_boards +++ b/resources/depthai_boards @@ -1 +1 @@ -Subproject commit 21b7b398821e63136d17754ef0a877b48d3a3680 +Subproject commit cb051ef1b4a5cc6a3f8cb676ae5a467f7bd91520 From 6bc315eabf393de09fb9d10dce0007847a3309a1 Mon Sep 17 00:00:00 2001 From: MaticTonin Date: Tue, 10 Feb 2026 10:59:16 +0100 Subject: [PATCH 3/3] Latest version, removal of flashCalibration2 --- calibrate.py | 68 ++++++++++++++++++++++++++-------------- depthai_calibration | 2 +- requirements.txt | 2 +- resources/depthai_boards | 2 +- 4 files changed, 48 insertions(+), 26 deletions(-) diff --git a/calibrate.py b/calibrate.py index 79760ebbb..85cac040f 100755 --- a/calibrate.py +++ b/calibrate.py @@ -1,24 +1,38 @@ #!/usr/bin/env python3 +from datetime import datetime, timedelta +from argparse import ArgumentParser +from collections import deque +from pathlib import Path +import itertools +import traceback import argparse + import json -from pydoc import render_doc import shutil -import traceback -from argparse import ArgumentParser -from pathlib import Path + import time -from datetime import datetime, timedelta -from collections import deque -from scipy.spatial.transform import Rotation -import traceback -import itertools import math import cv2 -from cv2 import resize +import sys +import os + +def check_opencv_version(REQUIRED_VERSION = "4.5.5"): + installed = cv2.__version__ + if installed != REQUIRED_VERSION: + print(f"[ERROR] OpenCV version mismatch!") + print(f"Installed: {installed}") + print(f"Required : {REQUIRED_VERSION}") + print("Please re-run:") + print(" pip install -r calib_requirements.txt") + sys.exit(1) + else: + print(f"[OK] OpenCV version {installed} is correct.") + +check_opencv_version() + import depthai as dai import numpy as np -import copy from packaging import version import sys @@ -168,7 +182,7 @@ def parse_args(): help="Enable the display of polynoms.") parser.add_argument('-dbg', '--debugProcessingMode', default=False, action="store_true", help="Enable processing of images without using the camera.") - parser.add_argument('-v3', '--useDepthaiV3', default=False, action="store_true", + parser.add_argument('-v3', '--useDepthaiV3', default=True, action="store_true", help="Use depthai v3.") options = parser.parse_args() # Set some extra defaults, `-brd` would override them @@ -599,17 +613,21 @@ def create_pipeline_v3(self): pipeline = dai.Pipeline(self.device) self.camera_queue = {} fps = self.args.framerate + sync = pipeline.create(dai.node.Sync) + sync.setSyncThreshold(timedelta(milliseconds=50)) for cam_id in self.board_config['cameras']: cam_info = self.board_config['cameras'][cam_id] if cam_info["name"] not in self.args.disableCamera: if cam_info['type'] == 'mono': - cam_node = pipeline.create(dai.node.Camera).build(stringToCam[cam_id]) - self.camera_queue[cam_info['name']] = cam_node.requestFullResolutionOutput(type=dai.ImgFrame.Type.NV12).createOutputQueue(blocking=False) + cam_node = pipeline.create(dai.node.Camera, fps = fps).build(stringToCam[cam_id]) + cam_output = cam_node.requestFullResolutionOutput(type=dai.ImgFrame.Type.NV12) + cam_output.link(sync.inputs[cam_info["name"]]) + self.camera_queue[cam_info['name']] = cam_output sensorName = cam_info['sensorName'] print(f'Sensor name for {cam_info["name"]} is {sensorName}') else: - cam_node = pipeline.create(dai.node.Camera).build(stringToCam[cam_id]) - self.camera_queue[cam_info['name']] = cam_node.requestFullResolutionOutput(type=dai.ImgFrame.Type.NV12).createOutputQueue(blocking=False) + cam_node = pipeline.create(dai.node.Camera, fps = fps).build(stringToCam[cam_id]) + self.camera_queue[cam_info['name']] = cam_node.requestFullResolutionOutput(type=dai.ImgFrame.Type.NV12).link(sync.inputs[cam_info["name"]]) if cam_info['sensorName'] == "OV9*82": cam_node.initialControl.setSharpness(0) cam_node.initialControl.setLumaDenoise(0) @@ -619,14 +637,13 @@ def create_pipeline_v3(self): if self.args.rgbLensPosition: cam_node.initialControl.setManualFocus(int(self.args.rgbLensPosition[stringToCam[cam_id].name.lower()])) else: - cam_node.initialControl.setManualFocusRaw(int(130 / 255)) + cam_node.initialControl.setManualFocusRaw(int(135 / 255)) - controlIn = pipeline.createXLinkIn() - controlIn.setStreamName(cam_info['name'] + '-control') - controlIn.out.link(cam_node.inputControl) + self.control_queue = cam_node.inputControl.createInputQueue() sensorName = cam_info['sensorName'] print(f'Sensor name for {cam_info["name"]} is {sensorName}') - cam_node.initialControl.setAntiBandingMode(antibandingOpts[self.args.antibanding]) + #cam_node.initialControl.setAntiBandingMode(antibandingOpts[self.args.antibanding]) + self.sync_queue = sync.out.createOutputQueue() return pipeline def parse_frame(self, frame, stream_name): @@ -766,8 +783,13 @@ def capture_images_sync(self): sync_trys = 0 while not finished: currImageList = {} + if self.args.useDepthaiV3: + msg_group = self.sync_queue.get() for key in self.camera_queue.keys(): - frameMsg = self.camera_queue[key].get() + if self.args.useDepthaiV3: + frameMsg = msg_group[key] + else: + frameMsg = self.camera_queue[key].get() #print(f'Timestamp of {key} is {frameMsg.getTimestamp()}') @@ -1143,7 +1165,7 @@ def calibrate(self): Path(self.args.saveCalibPath).parent.mkdir(parents=True, exist_ok=True) calibration_handler.eepromToJsonFile(self.args.saveCalibPath) # try: - self.device.flashCalibration2(calibration_handler) + self.device.flashCalibration(calibration_handler) is_write_succesful = True # except RuntimeError as e: # is_write_succesful = False diff --git a/depthai_calibration b/depthai_calibration index b18ab9e40..bedcf34b5 160000 --- a/depthai_calibration +++ b/depthai_calibration @@ -1 +1 @@ -Subproject commit b18ab9e40a8756c1b318da1bbecb2b3407e14463 +Subproject commit bedcf34b50151692b85adf71cf9425ce265216a8 diff --git a/requirements.txt b/requirements.txt index 59a3f1bc9..f47e361ca 100644 --- a/requirements.txt +++ b/requirements.txt @@ -6,7 +6,7 @@ opencv-contrib-python==4.5.5.62 # Last successful RPi build, also covers M1 with pyqt5>5,<5.15.6 ; platform_machine != "armv6l" and platform_machine != "armv7l" and platform_machine != "aarch64" and platform_machine != "arm64" --extra-index-url https://artifacts.luxonis.com/artifactory/luxonis-python-snapshot-local/ depthai -numpy>=1.21.4,<2.0.0 # For RPi Buster (last successful build) and macOS M1 (first build). But allow for higher versions, to support Python3.11 (not available in 1.21.4 yet) +numpy>=1.26.4,<2.0.0 # For RPi Buster (last successful build) and macOS M1 (first build). But allow for higher versions, to support Python3.11 (not available in 1.21.4 yet) Qt.py scipy matplotlib diff --git a/resources/depthai_boards b/resources/depthai_boards index cb051ef1b..aed25bd88 160000 --- a/resources/depthai_boards +++ b/resources/depthai_boards @@ -1 +1 @@ -Subproject commit cb051ef1b4a5cc6a3f8cb676ae5a467f7bd91520 +Subproject commit aed25bd8859b515f450253a3d5cb060274db2f24