Skip to content

Commit c412002

Browse files
committed
Merge remote-tracking branch 'origin/main' into tof_decoding
# Conflicts: # calibrate.py # depthai_sdk/requirements.txt
2 parents 9c7f6e4 + 933d575 commit c412002

32 files changed

+255
-209
lines changed

.github/workflows/test_install_requirements.yml

+2-2
Original file line numberDiff line numberDiff line change
@@ -91,9 +91,9 @@
9191
- name: Download chocolatey
9292
shell: pwsh
9393
run: Set-ExecutionPolicy Bypass -Scope Process -Force; [System.Net.ServicePointManager]::SecurityProtocol = [System.Net.ServicePointManager]::SecurityProtocol -bor 3072; iex ((New-Object System.Net.WebClient).DownloadString('https://chocolatey.org/install.ps1'))
94-
- name: Install dependencies
94+
- name: Install pycharm-community dependency
9595
shell: pwsh
96-
run: choco install cmake git python --version 3.10 pycharm-community -y
96+
run: choco install pycharm-community -y
9797
- name: Install requrirements
9898
run: |
9999
python install_requirements.py

calibrate.py

+40-66
Original file line numberDiff line numberDiff line change
@@ -164,6 +164,8 @@ def parse_args():
164164
help="Number of pictures taken.")
165165
parser.add_argument('-ebp', '--enablePolygonsDisplay', default=False, action="store_true",
166166
help="Enable the display of polynoms.")
167+
parser.add_argument('-dbg', '--debugProcessingMode', default=False, action="store_true",
168+
help="Enable processing of images without using the camera.")
167169
options = parser.parse_args()
168170
# Set some extra defaults, `-brd` would override them
169171
if options.defaultBoard is not None:
@@ -185,7 +187,10 @@ def parse_args():
185187
raise argparse.ArgumentTypeError("-s / --squareSizeCm needs to be greater than 2.2 cm")
186188
if options.traceLevel == 1:
187189
print(f"Charuco board selected is: board_name = {board_name}, numX = {numX}, numY = {numY}, squareSize {options.squareSizeCm} cm, markerSize {options.markerSizeCm} cm")
188-
190+
if options.debugProcessingMode:
191+
options.mode = "process"
192+
if options.board is None:
193+
raise argparse.ArgumentError(options.board, "Board name (-brd) of camera must be specified in case of using debug mode (-dbg).")
189194
return options
190195

191196
class HostSync:
@@ -350,31 +355,33 @@ def __init__(self):
350355
self.output_scale_factor = self.args.outputScaleFactor
351356
self.aruco_dictionary = cv2.aruco.Dictionary_get(
352357
cv2.aruco.DICT_4X4_1000)
353-
self.device = dai.Device()
354358
self.enablePolygonsDisplay = self.args.enablePolygonsDisplay
355359
self.board_name = None
356-
calibData = self.device.readCalibration()
357-
eeprom = calibData.getEepromData()
360+
if not self.args.debugProcessingMode:
361+
self.device = dai.Device()
362+
cameraProperties = self.device.getConnectedCameraFeatures()
363+
calibData = self.device.readCalibration()
364+
eeprom = calibData.getEepromData()
358365
#TODO Change only in getDeviceName in next revision.
359366
if self.args.board:
360367
self.board_name = self.args.board
361-
board_path = Path(self.args.board)
368+
board_path = Path(Path(__file__).parent /self.args.board)
362369
if not board_path.exists():
363370
board_path = (Path(__file__).parent / 'resources/depthai_boards/boards' / self.args.board.upper()).with_suffix('.json').resolve()
364371
if not board_path.exists():
365372
raise ValueError(
366-
'Board config not found: {}'.format(board_path))
373+
'Board config not found: {}'.format(Path(Path(__file__).parent /self.args.board)))
367374
with open(board_path) as fp:
368375
self.board_config = json.load(fp)
369376
self.board_config = self.board_config['board_config']
370377
self.board_config_backup = self.board_config
371-
else:
378+
elif not self.args.debugProcessingMode:
372379
try:
373380
detection = self.device.getDeviceName()
374381
print(f"Device name: {detection}")
375382
detection = detection.split("-")
376383
except:
377-
self.cameraProperties = self.device.getConnectedCameraFeatures()
384+
cameraProperties = self.device.getConnectedCameraFeatures()
378385
calibData = self.device.readCalibration()
379386
eeprom = calibData.getEepromData()
380387
eeprom.productName = eeprom.productName.replace(" ", "-").upper()
@@ -393,7 +400,7 @@ def __init__(self):
393400
if "9782" in detection:
394401
detection.remove("9782")
395402
self.board_name = '-'.join(detection)
396-
board_path = Path(self.board_name)
403+
board_path = Path(Path(__file__).parent /self.board_name)
397404
if self.traceLevel == 1:
398405
print(f"Board path specified as {board_path}")
399406
if not board_path.exists():
@@ -430,23 +437,18 @@ def __init__(self):
430437
for cam_id in self.board_config['cameras']:
431438
name = self.board_config['cameras'][cam_id]['name']
432439
self.coverageImages[name] = None
433-
434-
if (self._set_camera_features()):
435-
print("Camera features set using board config.")
436-
print(f"self.cameraProperties: {self.cameraProperties}")
437-
else:
438-
self.cameraProperties = self.device.getConnectedCameraFeatures()
439-
440-
for properties in self.cameraProperties:
441-
for in_cam in self.board_config['cameras'].keys():
442-
cam_info = self.board_config['cameras'][in_cam]
443-
if cam_info["name"] not in self.args.disableCamera:
444-
if properties.socket == stringToCam[in_cam]:
445-
self.board_config['cameras'][in_cam]['sensorName'] = properties.sensorName
446-
print('Cam: {} and focus: {}'.format(cam_info['name'], properties.hasAutofocus))
447-
self.board_config['cameras'][in_cam]['hasAutofocus'] = properties.hasAutofocus
448-
# self.auto_checkbox_dict[cam_info['name'] + '-Camera-connected'].check()
449-
break
440+
if not self.args.debugProcessingMode:
441+
cameraProperties = self.device.getConnectedCameraFeatures()
442+
for properties in cameraProperties:
443+
for in_cam in self.board_config['cameras'].keys():
444+
cam_info = self.board_config['cameras'][in_cam]
445+
if cam_info["name"] not in self.args.disableCamera:
446+
if properties.socket == stringToCam[in_cam]:
447+
self.board_config['cameras'][in_cam]['sensorName'] = properties.sensorName
448+
print('Cam: {} and focus: {}'.format(cam_info['name'], properties.hasAutofocus))
449+
self.board_config['cameras'][in_cam]['hasAutofocus'] = properties.hasAutofocus
450+
# self.auto_checkbox_dict[cam_info['name'] + '-Camera-connected'].check()
451+
break
450452

451453
self.charuco_board = cv2.aruco.CharucoBoard_create(
452454
self.args.squaresX, self.args.squaresY,
@@ -459,39 +461,6 @@ def mouse_event_callback(self, event, x, y, flags, param):
459461
if event == cv2.EVENT_LBUTTONDOWN:
460462
self.mouseTrigger = True
461463

462-
def _set_camera_features(self):
463-
"""
464-
Create mock camera properties using manually specified board config
465-
"""
466-
467-
self.cameraProperties = self.device.getConnectedCameraFeatures()
468-
469-
for cam_id in self.board_config['cameras']:
470-
try:
471-
sensor_model = self.board_config['cameras'][cam_id]["model"]
472-
config_type = self.board_config['cameras'][cam_id]["type"]
473-
except KeyError:
474-
print(f"Model not found for {cam_id}, skipping...")
475-
return False
476-
477-
if sensor_model in camToRgbRes:
478-
supportedTypes = [dai.CameraSensorType.COLOR]
479-
elif sensor_model in camToMonoRes:
480-
supportedTypes = [dai.CameraSensorType.MONO]
481-
else:
482-
print(f"Model {sensor_model} not supported")
483-
return False
484-
485-
if supportedTypes[0].name != config_type.upper():
486-
raise ValueError(f"Mismatch in camera type for {cam_id} with model {sensor_model} and type {config_type}, please fix the board config.")
487-
488-
for cam in self.cameraProperties:
489-
if stringToCam[cam_id] == cam.socket:
490-
cam.sensorName = sensor_model
491-
cam.supportedTypes = supportedTypes
492-
493-
return True
494-
495464
def startPipeline(self):
496465
pipeline = self.create_pipeline()
497466
self.device.startPipeline(pipeline)
@@ -1006,7 +975,7 @@ def calibrate(self):
1006975
self.args.cameraMode,
1007976
self.args.rectifiedDisp) # Turn off enable disp rectify
1008977

1009-
if self.args.noInitCalibration:
978+
if self.args.noInitCalibration or self.args.debugProcessingMode:
1010979
calibration_handler = dai.CalibrationHandler()
1011980
else:
1012981
calibration_handler = self.device.readCalibration()
@@ -1019,7 +988,8 @@ def calibrate(self):
1019988
calibration_handler.setBoardInfo(str(self.device.getDeviceName()), str(self.args.revision))
1020989
except Exception as e:
1021990
print('Device closed in exception..' )
1022-
self.device.close()
991+
if not self.args.debugProcessingMode:
992+
self.device.close()
1023993
print(e)
1024994
print(traceback.format_exc())
1025995
raise SystemExit(1)
@@ -1104,7 +1074,7 @@ def calibrate(self):
11041074
calibration_handler.setStereoLeft(stringToCam[cam_info['extrinsics']['to_cam']], result_config['stereo_config']['rectification_left'])
11051075
target_file.close()
11061076

1107-
if len(error_text) == 0:
1077+
if len(error_text) == 0 and not self.args.debugProcessingMode:
11081078
print('Flashing Calibration data into ')
11091079
# print(calib_dest_path)
11101080

@@ -1138,15 +1108,17 @@ def calibrate(self):
11381108
is_write_factory_sucessful = False
11391109

11401110
if is_write_succesful:
1141-
self.device.close()
1111+
if not self.args.debugProcessingMode:
1112+
self.device.close()
11421113
text = "EEPROM written succesfully"
11431114
resImage = create_blank(900, 512, rgb_color=green)
11441115
cv2.putText(resImage, text, (10, 250), font, 2, (0, 0, 0), 2)
11451116
cv2.imshow("Result Image", resImage)
11461117
cv2.waitKey(0)
11471118

11481119
else:
1149-
self.device.close()
1120+
if not self.args.debugProcessingMode:
1121+
self.device.close()
11501122
text = "EEPROM write Failed!!"
11511123
resImage = create_blank(900, 512, rgb_color=red)
11521124
cv2.putText(resImage, text, (10, 250), font, 2, (0, 0, 0), 2)
@@ -1155,7 +1127,8 @@ def calibrate(self):
11551127
# return (False, "EEPROM write Failed!!")
11561128

11571129
else:
1158-
self.device.close()
1130+
if not self.args.debugProcessingMode:
1131+
self.device.close()
11591132
print(error_text)
11601133
for text in error_text:
11611134
# text = error_text[0]
@@ -1164,7 +1137,8 @@ def calibrate(self):
11641137
cv2.imshow("Result Image", resImage)
11651138
cv2.waitKey(0)
11661139
except Exception as e:
1167-
self.device.close()
1140+
if not self.args.debugProcessingMode:
1141+
self.device.close()
11681142
print('Device closed in exception..' )
11691143
print(e)
11701144
print(traceback.format_exc())

depthai_demo.py

+3-2
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,8 @@ def setup(self, conf: ConfigManager):
206206
self._nnManager.countLabel(self._conf.getCountLabel(self._nnManager))
207207
self._pm.setNnManager(self._nnManager)
208208

209-
self._device = dai.Device(self._pm.pipeline.getOpenVINOVersion(), self._deviceInfo, usb2Mode=self._conf.args.usbSpeed == "usb2")
209+
maxUsbSpeed = dai.UsbSpeed.HIGH if self._conf.args.usbSpeed == "usb2" else dai.UsbSpeed.SUPER
210+
self._device = dai.Device(self._pm.pipeline.getOpenVINOVersion(), self._deviceInfo, maxUsbSpeed)
210211
self._device.addLogCallback(self._logMonitorCallback)
211212
if sentryEnabled:
212213
try:
@@ -288,7 +289,7 @@ def run(self):
288289

289290
if self._conf.useCamera:
290291
cameras = self._device.getConnectedCameras()
291-
if dai.CameraBoardSocket.LEFT in cameras and dai.CameraBoardSocket.RIGHT in cameras:
292+
if dai.CameraBoardSocket.CAM_B in cameras and dai.CameraBoardSocket.CAM_C in cameras:
292293
self._pv.collectCalibData(self._device)
293294

294295
self._updateCameraConfigs({

depthai_sdk/docs/source/components/stereo_component.rst

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
StereoComponent
22
===============
33

4-
:class:`StereoComponent <depthai_sdk.components.StereoComponent>` abstracts `StereoDepth <https://docs.luxonis.com/projects/api/en/latest/components/nodes/imu/>`__ node, its configuration,
4+
:class:`StereoComponent <depthai_sdk.components.StereoComponent>` abstracts `StereoDepth <https://docs.luxonis.com/projects/api/en/latest/components/nodes/stereo_depth/>`__ node, its configuration,
55
filtering (eg. `WLS filter <https://github.com/luxonis/depthai-experiments/tree/master/gen2-wls-filter>`__), and disparity/depth viewing.
66

77
Usage
@@ -35,4 +35,4 @@ Reference
3535

3636
.. autoclass:: depthai_sdk.components.StereoComponent
3737
:members:
38-
:undoc-members:
38+
:undoc-members:

depthai_sdk/docs/source/samples/mixed/sdk_sync_multiple_outputs.rst

+2-2
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,8 @@ Source Code
3434

3535
Also `available on GitHub <https://github.com/luxonis/depthai/tree/main/depthai_sdk/examples/CameraComponent/sync_multiple_outputs.py>`__
3636

37-
.. literalinclude:: ../../../../examples/CameraComponent/sync_multiple_outputs.py
37+
.. literalinclude:: ../../../../examples/mixed/sync_multiple_outputs.py
3838
:language: python
3939
:linenos:
4040

41-
.. include:: /includes/footer-short.rst
41+
.. include:: /includes/footer-short.rst

depthai_sdk/examples/IMUComponent/imu.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -5,5 +5,5 @@
55
imu.config_imu(report_rate=400, batch_report_threshold=5)
66
# DepthAI viewer should open, and IMU data can be viewed on the right-side panel,
77
# under "Stats" tab (right of the "Device Settings" tab).
8-
oak.visualize(imu.out.main, visualizer='viewer')
8+
oak.visualize(imu.out.main)
99
oak.start(blocking=True)

depthai_sdk/src/depthai_sdk/classes/packet_handlers.py

+3-2
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
import logging
1+
22
import os
33
from abc import abstractmethod
44
from queue import Queue, Empty
@@ -8,6 +8,7 @@
88

99
from depthai_sdk.classes.packets import BasePacket
1010
from depthai_sdk.components.component import Component, ComponentOutput
11+
from depthai_sdk.logger import LOGGER
1112
from depthai_sdk.oak_outputs.fps import FPS
1213
from depthai_sdk.oak_outputs.syncing import TimestampSync
1314
from depthai_sdk.oak_outputs.xout.xout_base import XoutBase, ReplayStream
@@ -65,7 +66,7 @@ def configure_syncing(self,
6566
"""
6667
if enable_sync:
6768
if len(self.outputs) < 2:
68-
logging.error('Syncing requires at least 2 outputs! Skipping syncing.')
69+
LOGGER.error('Syncing requires at least 2 outputs! Skipping syncing.')
6970
return
7071
self.sync = TimestampSync(len(self.outputs), threshold_ms)
7172

depthai_sdk/src/depthai_sdk/components/camera_component.py

+4-4
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
1-
import logging
21
from typing import Dict
32

43
from depthai_sdk.classes.enum import ResizeMode
54
from depthai_sdk.components.camera_control import CameraControl
65
from depthai_sdk.components.camera_helper import *
76
from depthai_sdk.components.component import Component, ComponentOutput
87
from depthai_sdk.components.parser import parse_resolution, parse_encode, encoder_profile_to_fourcc
8+
from depthai_sdk.logger import LOGGER
99
from depthai_sdk.oak_outputs.xout.xout_base import XoutBase, StreamXout, ReplayStream
1010
from depthai_sdk.oak_outputs.xout.xout_frames import XoutFrames
1111
from depthai_sdk.replay import Replay
@@ -297,7 +297,7 @@ def control_with_nn(self, detection_component: 'NNComponent', auto_focus=True, a
297297
"""
298298

299299
if not auto_focus and not auto_exposure:
300-
logging.error('Attempted to control camera with NN, '
300+
LOGGER.error('Attempted to control camera with NN, '
301301
'but both Auto-Focus and Auto-Exposure were disabled! Attempt ignored.')
302302
return
303303

@@ -337,12 +337,12 @@ def config_color_camera(self,
337337
chroma_denoise: Optional[int] = None,
338338
) -> None:
339339
if not self.is_color():
340-
logging.info('Attempted to configure ColorCamera, '
340+
LOGGER.info('Attempted to configure ColorCamera, '
341341
'but this component doesn\'t have it. Config attempt ignored.')
342342
return
343343

344344
if self.is_replay():
345-
logging.info('Tried configuring ColorCamera, but replaying is enabled. Config attempt ignored.')
345+
LOGGER.info('Tried configuring ColorCamera, but replaying is enabled. Config attempt ignored.')
346346
return
347347

348348
if interleaved is not None: self.node.setInterleaved(interleaved)

0 commit comments

Comments
 (0)