diff --git a/CMakeLists.txt b/CMakeLists.txt index d8fc4fee8..cddfd09ba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -129,6 +129,8 @@ pybind11_add_module(${TARGET_NAME} src/pipeline/node/WarpBindings.cpp src/pipeline/node/UVCBindings.cpp src/pipeline/node/ToFBindings.cpp + src/pipeline/node/SyncBindings.cpp + src/pipeline/node/MessageDemuxBindings.cpp src/pipeline/datatype/ADatatypeBindings.cpp src/pipeline/datatype/AprilTagConfigBindings.cpp @@ -141,7 +143,9 @@ pybind11_add_module(${TARGET_NAME} src/pipeline/datatype/ImageManipConfigBindings.cpp src/pipeline/datatype/ImgDetectionsBindings.cpp src/pipeline/datatype/ImgFrameBindings.cpp + src/pipeline/datatype/EncodedFrameBindings.cpp src/pipeline/datatype/IMUDataBindings.cpp + src/pipeline/datatype/MessageGroupBindings.cpp src/pipeline/datatype/NNDataBindings.cpp src/pipeline/datatype/SpatialImgDetectionsBindings.cpp src/pipeline/datatype/SpatialLocationCalculatorConfigBindings.cpp @@ -173,8 +177,8 @@ endif() # Add stubs (pyi) generation step after building bindings execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" "from mypy import api" RESULT_VARIABLE error OUTPUT_QUIET ERROR_QUIET) -if(error) - message(WARNING "Mypy not available - stubs won't be generated or checked") +if(error OR CMAKE_CROSSCOMPILING) + message(WARNING "Mypy not available or cross compiling - stubs won't be generated or checked") else() get_target_property(bindings_directory ${TARGET_NAME} LIBRARY_OUTPUT_DIRECTORY) if(NOT bindings_directory) diff --git a/depthai-core b/depthai-core index bcd7a0e25..6628488ef 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit bcd7a0e258a264f93ad249acf248bbc8ee617746 +Subproject commit 6628488ef8956f73f1c7bf4c8f1da218ad327a6f diff --git a/docs/source/conf.py b/docs/source/conf.py index 44d44c233..c99a90c4c 100644 --- a/docs/source/conf.py +++ b/docs/source/conf.py @@ -22,7 +22,7 @@ subprocess.check_call(['make', 'install'], cwd=tmpdir+'/libusb-1.0.24') env['PATH'] = tmpdir+'/libusb/include:'+tmpdir+'/libusb/lib'+':'+env['PATH'] -# Not needed anymore, part of pip install that carries the binary itself also +# Not needed since libclang usage in pip requirements (brings its own library) # # libclang # subprocess.check_call(['wget', 'https://artifacts.luxonis.com/artifactory/luxonis-depthai-data-local/misc/libclang-11_manylinux2014_x86_64.tar.xz'], cwd=tmpdir) # subprocess.check_call(['mkdir', '-p', 'libclang'], cwd=tmpdir) diff --git a/examples/MonoCamera/mono_preview_alternate_pro.py b/examples/MonoCamera/mono_preview_alternate_pro.py index 6f5997150..9d6e53800 100755 --- a/examples/MonoCamera/mono_preview_alternate_pro.py +++ b/examples/MonoCamera/mono_preview_alternate_pro.py @@ -43,8 +43,8 @@ script = pipeline.create(dai.node.Script) script.setProcessor(dai.ProcessorType.LEON_CSS) script.setScript(""" - dotBright = 500 # Note: recommended to not exceed 765, for max duty cycle - floodBright = 200 + dotBright = 0.8 + floodBright = 0.1 LOGGING = False # Set `True` for latency/timings debugging node.warn(f'IR drivers detected: {str(Device.getIrDrivers())}') @@ -57,8 +57,8 @@ # Immediately reconfigure the IR driver. # Note the logic is inverted, as it applies for next frame - Device.setIrLaserDotProjectorBrightness(0 if flagDot else dotBright) - Device.setIrFloodLightBrightness(floodBright if flagDot else 0) + Device.setIrLaserDotProjectorIntensity(0 if flagDot else dotBright) + Device.setIrFloodLightIntensity(floodBright if flagDot else 0) if LOGGING: tIrSet = Clock.now() # Wait for the actual frames (after MIPI capture and ISP proc is done) diff --git a/examples/StereoDepth/stereo_depth_from_host.py b/examples/StereoDepth/stereo_depth_from_host.py index 08f4c06b8..971886678 100755 --- a/examples/StereoDepth/stereo_depth_from_host.py +++ b/examples/StereoDepth/stereo_depth_from_host.py @@ -17,6 +17,9 @@ parser.add_argument("-e", "--evaluate", help="Evaluate the disparity calculation.", default=None) parser.add_argument("-dumpdispcost", "--dumpdisparitycostvalues", action="store_true", help="Dumps the disparity cost values for each disparity range. 96 byte for each pixel.") parser.add_argument("--download", action="store_true", help="Downloads the 2014 Middlebury dataset.") +parser.add_argument("--calibration", help="Path to calibration file", default=None) +parser.add_argument("--rectify", action="store_true", help="Enable rectified streams") +parser.add_argument("--swapLR", action="store_true", help="Swap left and right cameras.") args = parser.parse_args() if args.evaluate is not None and args.dataset is not None: @@ -603,8 +606,12 @@ def __init__(self, config): stereo.setRuntimeModeSwitch(True) # Linking -monoLeft.out.link(stereo.left) -monoRight.out.link(stereo.right) +if(args.swapLR): + monoLeft.out.link(stereo.right) + monoRight.out.link(stereo.left) +else: + monoLeft.out.link(stereo.left) + monoRight.out.link(stereo.right) xinStereoDepthConfig.out.link(stereo.inputConfig) stereo.syncedLeft.link(xoutLeft.input) stereo.syncedRight.link(xoutRight.input) @@ -630,9 +637,11 @@ def __init__(self, config): StereoConfigHandler.registerWindow("Stereo control panel") # stereo.setPostProcessingHardwareResources(3, 3) - +if(args.calibration): + calibrationHandler = dai.CalibrationHandler(args.calibration) + pipeline.setCalibrationData(calibrationHandler) stereo.setInputResolution(width, height) -stereo.setRectification(False) +stereo.setRectification(args.rectify) baseline = 75 fov = 71.86 focal = width / (2 * math.tan(fov / 2 / 180 * math.pi)) diff --git a/examples/Sync/demux_message_group.py b/examples/Sync/demux_message_group.py new file mode 100644 index 000000000..41c488f9c --- /dev/null +++ b/examples/Sync/demux_message_group.py @@ -0,0 +1,57 @@ +import depthai as dai +import time +from datetime import timedelta + +pipeline = dai.Pipeline() + +script1 = pipeline.create(dai.node.Script) +script1.setScript(""" +from time import sleep + +while True: + sleep(1) + b = Buffer(512) + b.setData(bytes(4 * [i for i in range(0, 128)])) + b.setTimestamp(Clock.now()) + node.io['out'].send(b) +""") + +script2 = pipeline.create(dai.node.Script) +script2.setScript(""" +from time import sleep + +while True: + sleep(0.3) + b = Buffer(512) + b.setData(bytes(4 * [i for i in range(128, 256)])) + b.setTimestamp(Clock.now()) + node.io['out'].send(b) +""") + +sync = pipeline.create(dai.node.Sync) +sync.setSyncThresholdMs(timedelta(milliseconds=100)) + +demux = pipeline.create(dai.node.MessageDemux) + +xout1 = pipeline.create(dai.node.XLinkOut) +xout1.setStreamName("xout1") +xout2 = pipeline.create(dai.node.XLinkOut) +xout2.setStreamName("xout2") + +script1.outputs["out"].link(sync.inputs["s1"]) +script2.outputs["out"].link(sync.inputs["s2"]) +sync.out.link(demux.input) +demux.outputs["s1"].link(xout1.input) +demux.outputs["s2"].link(xout2.input) + +with dai.Device(pipeline) as device: + print("Start") + q1 = device.getOutputQueue("xout1", maxSize=10, blocking=True) + q2 = device.getOutputQueue("xout2", maxSize=10, blocking=True) + while True: + bufS1 = q1.get() + bufS2 = q2.get() + print(f"Buffer 1 timestamp: {bufS1.getTimestamp()}") + print(f"Buffer 2 timestamp: {bufS2.getTimestamp()}") + print("----------") + time.sleep(0.2) diff --git a/examples/Sync/depth_video_synced.py b/examples/Sync/depth_video_synced.py new file mode 100644 index 000000000..bd1c85cef --- /dev/null +++ b/examples/Sync/depth_video_synced.py @@ -0,0 +1,49 @@ +import depthai as dai +import numpy as np +import cv2 +from datetime import timedelta + +pipeline = dai.Pipeline() + +monoLeft = pipeline.create(dai.node.MonoCamera) +monoRight = pipeline.create(dai.node.MonoCamera) +color = pipeline.create(dai.node.ColorCamera) +stereo = pipeline.create(dai.node.StereoDepth) +sync = pipeline.create(dai.node.Sync) + +xoutGrp = pipeline.create(dai.node.XLinkOut) + +xoutGrp.setStreamName("xout") + +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoLeft.setCamera("left") +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoRight.setCamera("right") + +stereo.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_ACCURACY) + +color.setCamera("color") + +sync.setSyncThreshold(timedelta(milliseconds=50)) + +monoLeft.out.link(stereo.left) +monoRight.out.link(stereo.right) + +stereo.disparity.link(sync.inputs["disparity"]) +color.video.link(sync.inputs["video"]) + +sync.out.link(xoutGrp.input) + +disparityMultiplier = 255.0 / stereo.initialConfig.getMaxDisparity() +with dai.Device(pipeline) as device: + queue = device.getOutputQueue("xout", 10, False) + while True: + msgGrp = queue.get() + for name, msg in msgGrp: + frame = msg.getCvFrame() + if name == "disparity": + frame = (frame * disparityMultiplier).astype(np.uint8) + frame = cv2.applyColorMap(frame, cv2.COLORMAP_JET) + cv2.imshow(name, frame) + if cv2.waitKey(1) == ord("q"): + break diff --git a/examples/Sync/imu_video_synced.py b/examples/Sync/imu_video_synced.py new file mode 100644 index 000000000..7fbede660 --- /dev/null +++ b/examples/Sync/imu_video_synced.py @@ -0,0 +1,59 @@ +import depthai as dai +import numpy as np +import cv2 +from datetime import timedelta + +device = dai.Device() + +imuType = device.getConnectedIMU() +imuFirmwareVersion = device.getIMUFirmwareVersion() +print(f"IMU type: {imuType}, firmware version: {imuFirmwareVersion}") + +if imuType != "BNO086": + print("Rotation vector output is supported only by BNO086!") + exit(0) + +pipeline = dai.Pipeline() + +color = pipeline.create(dai.node.ColorCamera) +imu = pipeline.create(dai.node.IMU) +sync = pipeline.create(dai.node.Sync) +xoutImu = pipeline.create(dai.node.XLinkOut) +xoutImu.setStreamName("imu") + +xoutGrp = pipeline.create(dai.node.XLinkOut) +xoutGrp.setStreamName("xout") + +color.setCamera("color") + +imu.enableIMUSensor(dai.IMUSensor.ROTATION_VECTOR, 120) +imu.setBatchReportThreshold(1) +imu.setMaxBatchReports(10) + +sync.setSyncThreshold(timedelta(milliseconds=10)) +sync.setSyncAttempts(-1) + +color.video.link(sync.inputs["video"]) +imu.out.link(sync.inputs["imu"]) + +sync.out.link(xoutGrp.input) + + +with device: + device.startPipeline(pipeline) + groupQueue = device.getOutputQueue("xout", 3, True) + while True: + groupMessage = groupQueue.get() + imuMessage = groupMessage["imu"] + colorMessage = groupMessage["video"] + print() + print("Device timestamp imu: " + str(imuMessage.getTimestampDevice())) + print("Device timestamp video:" + str(colorMessage.getTimestampDevice())) + latestRotationVector = imuMessage.packets[-1].rotationVector + imuF = "{:.4f}" + print(f"Quaternion: i: {imuF.format(latestRotationVector.i)} j: {imuF.format(latestRotationVector.j)} " + f"k: {imuF.format(latestRotationVector.k)} real: {imuF.format(latestRotationVector.real)}") + print() + cv2.imshow("video", colorMessage.getCvFrame()) + if cv2.waitKey(1) == ord("q"): + break diff --git a/examples/Sync/sync_scripts.py b/examples/Sync/sync_scripts.py new file mode 100644 index 000000000..3309dec8d --- /dev/null +++ b/examples/Sync/sync_scripts.py @@ -0,0 +1,53 @@ +import depthai as dai +import time +from datetime import timedelta + +pipeline = dai.Pipeline() + +script1 = pipeline.create(dai.node.Script) +script1.setScript(""" +from time import sleep + +while True: + sleep(1) + b = Buffer(512) + b.setData(bytes(4 * [i for i in range(0, 128)])) + b.setTimestamp(Clock.now()) + node.io['out'].send(b) +""") + +script2 = pipeline.create(dai.node.Script) +script2.setScript(""" +from time import sleep + +while True: + sleep(0.3) + b = Buffer(512) + b.setData(bytes(4 * [i for i in range(128, 256)])) + b.setTimestamp(Clock.now()) + node.io['out'].send(b) +""") + +sync = pipeline.create(dai.node.Sync) +sync.setSyncThreshold(timedelta(milliseconds=100)) + +xout = pipeline.create(dai.node.XLinkOut) +xout.setStreamName("xout") + +sync.out.link(xout.input) + +script1.outputs["out"].link(sync.inputs["s1"]) +script2.outputs["out"].link(sync.inputs["s2"]) + +# script1.outputs["out"].link(xout.input) + +with dai.Device(pipeline) as device: + print("Start") + q = device.getOutputQueue("xout", maxSize=10, blocking=True) + while True: + grp = q.get() + for name, msg in grp: + print(f"Received {name} with timestamp {msg.getTimestamp()}") + print(f"Time interval between messages: {grp.getIntervalNs() / 1e6}ms") + print("----------") + time.sleep(0.2) diff --git a/examples/VideoEncoder/rgb_encoding_encodedframe.py b/examples/VideoEncoder/rgb_encoding_encodedframe.py new file mode 100755 index 000000000..febea0ef1 --- /dev/null +++ b/examples/VideoEncoder/rgb_encoding_encodedframe.py @@ -0,0 +1,69 @@ +#!/usr/bin/env python3 + +import depthai as dai + +def frametype2str(ft): + if ft == dai.EncodedFrame.FrameType.I: + return "I" + elif ft == dai.EncodedFrame.FrameType.P: + return "P" + elif ft == dai.EncodedFrame.FrameType.B: + return "B" + +def compress(ls): + curr = ls[0] + count = 1 + res = [] + for i in range(1, len(ls)): + if ls[i] == curr: + count += 1 + else: + res.append((count, curr)) + curr = ls[i] + count = 1 + res.append((count, curr)) + return res + + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and output +camRgb = pipeline.create(dai.node.ColorCamera) +videoEnc = pipeline.create(dai.node.VideoEncoder) +xout = pipeline.create(dai.node.XLinkOut) + +xout.setStreamName('h265') + +# Properties +camRgb.setBoardSocket(dai.CameraBoardSocket.CAM_A) +camRgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_4_K) +videoEnc.setDefaultProfilePreset(30, dai.VideoEncoderProperties.Profile.H265_MAIN) + +# Linking +camRgb.video.link(videoEnc.input) +videoEnc.out.link(xout.input) + +frametypes = [] +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + + # Output queue will be used to get the encoded data from the output defined above + q = device.getOutputQueue(name="h265", maxSize=30, blocking=True) + + # The .h265 file is a raw stream file (not playable yet) + with open('video.h265', 'wb') as videoFile: + print("Press Ctrl+C to stop encoding...") + try: + while True: + h265Packet = q.get() # Blocking call, will wait until a new data has arrived + frametypes.append(frametype2str(h265Packet.getFrameType())) + h265Packet.getData().tofile(videoFile) # Appends the packet data to the opened file + except KeyboardInterrupt: + # Keyboard interrupt (Ctrl + C) detected + pass + + print("To view the encoded data, convert the stream file (.h265) into a video file (.mp4) using a command below:") + print("ffmpeg -framerate 30 -i video.h265 -c copy video.mp4") + +print(",".join([f"{c}{f}" for c, f in compress(frametypes)])) diff --git a/setup.py b/setup.py index 341ab5f24..7dfd75015 100644 --- a/setup.py +++ b/setup.py @@ -142,6 +142,11 @@ def build_extension(self, ext): freeMemory = 4000 # Configure and build + + # Add additional cmake build args from environment + if 'CMAKE_BUILD_ARGS' in os.environ: + build_args += [os.environ['CMAKE_BUILD_ARGS']] + # Windows if platform.system() == "Windows": cmake_args += ['-DCMAKE_LIBRARY_OUTPUT_DIRECTORY_{}={}'.format(cfg.upper(), extdir)] diff --git a/src/DataQueueBindings.cpp b/src/DataQueueBindings.cpp index 557ae573f..f940dfd2c 100644 --- a/src/DataQueueBindings.cpp +++ b/src/DataQueueBindings.cpp @@ -51,7 +51,7 @@ void DataQueueBindings::bind(pybind11::module& m, void* pCallstack){ dataOutputQueue .def("getName", &DataOutputQueue::getName, DOC(dai, DataOutputQueue, getName)) .def("isClosed", &DataOutputQueue::isClosed, DOC(dai, DataOutputQueue, isClosed)) - .def("close", &DataOutputQueue::close, DOC(dai, DataOutputQueue, close)) + .def("close", &DataOutputQueue::close, DOC(dai, DataOutputQueue, close), py::call_guard()) .def("addCallback", addCallbackLambda, py::arg("callback"), DOC(dai, DataOutputQueue, addCallback)) .def("addCallback", addCallbackLambda, py::arg("callback"), DOC(dai, DataOutputQueue, addCallback, 2)) @@ -114,7 +114,7 @@ void DataQueueBindings::bind(pybind11::module& m, void* pCallstack){ // Bind DataInputQueue dataInputQueue .def("isClosed", &DataInputQueue::isClosed, DOC(dai, DataInputQueue, isClosed)) - .def("close", &DataInputQueue::close, DOC(dai, DataInputQueue, close)) + .def("close", &DataInputQueue::close, DOC(dai, DataInputQueue, close), py::call_guard()) .def("getName", &DataInputQueue::getName, DOC(dai, DataInputQueue, getName)) .def("setBlocking", &DataInputQueue::setBlocking, py::arg("blocking"), DOC(dai, DataInputQueue, setBlocking)) .def("getBlocking", &DataInputQueue::getBlocking, DOC(dai, DataInputQueue, getBlocking)) diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 5ff683f3d..fab061f01 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -13,7 +13,9 @@ void bind_featuretrackerconfig(pybind11::module& m, void* pCallstack); void bind_imagemanipconfig(pybind11::module& m, void* pCallstack); void bind_imgdetections(pybind11::module& m, void* pCallstack); void bind_imgframe(pybind11::module& m, void* pCallstack); +void bind_encodedframe(pybind11::module& m, void* pCallstack); void bind_imudata(pybind11::module& m, void* pCallstack); +void bind_message_group(pybind11::module& m, void* pCallstack); void bind_nndata(pybind11::module& m, void* pCallstack); void bind_spatialimgdetections(pybind11::module& m, void* pCallstack); void bind_spatiallocationcalculatorconfig(pybind11::module& m, void* pCallstack); @@ -39,7 +41,9 @@ void DatatypeBindings::addToCallstack(std::deque& callstack) { callstack.push_front(bind_imagemanipconfig); callstack.push_front(bind_imgdetections); callstack.push_front(bind_imgframe); + callstack.push_front(bind_encodedframe); callstack.push_front(bind_imudata); + callstack.push_front(bind_message_group); callstack.push_front(bind_nndata); callstack.push_front(bind_spatialimgdetections); callstack.push_front(bind_spatiallocationcalculatorconfig); @@ -74,6 +78,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ datatypeEnum .value("Buffer", DatatypeEnum::Buffer) .value("ImgFrame", DatatypeEnum::ImgFrame) + .value("EncodedFrame", DatatypeEnum::EncodedFrame) .value("NNData", DatatypeEnum::NNData) .value("ImageManipConfig", DatatypeEnum::ImageManipConfig) .value("CameraControl", DatatypeEnum::CameraControl) diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 447ab9f81..f994e9022 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -611,6 +611,7 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ .def("getCrashDump", [](DeviceBase& d, bool clearCrashDump) { py::gil_scoped_release release; return d.getCrashDump(clearCrashDump); }, py::arg("clearCrashDump") = true, DOC(dai, DeviceBase, getCrashDump)) .def("hasCrashDump", [](DeviceBase& d) { py::gil_scoped_release release; return d.hasCrashDump(); }, DOC(dai, DeviceBase, hasCrashDump)) .def("getConnectedCameras", [](DeviceBase& d) { py::gil_scoped_release release; return d.getConnectedCameras(); }, DOC(dai, DeviceBase, getConnectedCameras)) + .def("getConnectionInterfaces", [](DeviceBase& d) { py::gil_scoped_release release; return d.getConnectionInterfaces(); }, DOC(dai, DeviceBase, getConnectionInterfaces)) .def("getConnectedCameraFeatures", [](DeviceBase& d) { py::gil_scoped_release release; return d.getConnectedCameraFeatures(); }, DOC(dai, DeviceBase, getConnectedCameraFeatures)) .def("getCameraSensorNames", [](DeviceBase& d) { py::gil_scoped_release release; return d.getCameraSensorNames(); }, DOC(dai, DeviceBase, getCameraSensorNames)) .def("getConnectedIMU", [](DeviceBase& d) { py::gil_scoped_release release; return d.getConnectedIMU(); }, DOC(dai, DeviceBase, getConnectedIMU)) @@ -635,8 +636,26 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ .def("flashCalibration", [](DeviceBase& d, CalibrationHandler calibrationDataHandler) { py::gil_scoped_release release; return d.flashCalibration(calibrationDataHandler); }, py::arg("calibrationDataHandler"), DOC(dai, DeviceBase, flashCalibration)) .def("setXLinkChunkSize", [](DeviceBase& d, int s) { py::gil_scoped_release release; d.setXLinkChunkSize(s); }, py::arg("sizeBytes"), DOC(dai, DeviceBase, setXLinkChunkSize)) .def("getXLinkChunkSize", [](DeviceBase& d) { py::gil_scoped_release release; return d.getXLinkChunkSize(); }, DOC(dai, DeviceBase, getXLinkChunkSize)) - .def("setIrLaserDotProjectorBrightness", [](DeviceBase& d, float m, int mask) { py::gil_scoped_release release; return d.setIrLaserDotProjectorBrightness(m, mask); }, py::arg("mA"), py::arg("mask") = -1, DOC(dai, DeviceBase, setIrLaserDotProjectorBrightness)) - .def("setIrFloodLightBrightness", [](DeviceBase& d, float m, int mask) { py::gil_scoped_release release; return d.setIrFloodLightBrightness(m, mask); }, py::arg("mA"), py::arg("mask") = -1, DOC(dai, DeviceBase, setIrFloodLightBrightness)) + .def("setIrLaserDotProjectorBrightness", [](DeviceBase& d, float mA, int mask) { + PyErr_WarnEx(PyExc_DeprecationWarning, "Use setIrLaserDotProjectorIntensity() instead.", 1); + HEDLEY_DIAGNOSTIC_PUSH + HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + py::gil_scoped_release release; + bool result = d.setIrLaserDotProjectorBrightness(mA, mask); + HEDLEY_DIAGNOSTIC_POP + return result; + }, py::arg("mA"), py::arg("mask") = -1, DOC(dai, DeviceBase, setIrLaserDotProjectorBrightness)) + .def("setIrFloodLightBrightness", [](DeviceBase& d, float mA, int mask) { + PyErr_WarnEx(PyExc_DeprecationWarning, "Use setIrFloodLightIntensity() instead.", 1); + HEDLEY_DIAGNOSTIC_PUSH + HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + py::gil_scoped_release release; + bool result = d.setIrFloodLightBrightness(mA, mask); + HEDLEY_DIAGNOSTIC_POP + return result; + }, py::arg("mA"), py::arg("mask") = -1, DOC(dai, DeviceBase, setIrFloodLightBrightness)) + .def("setIrLaserDotProjectorIntensity", [](DeviceBase& d, float intensity, int mask) { py::gil_scoped_release release; return d.setIrLaserDotProjectorIntensity(intensity, mask); }, py::arg("intensity"), py::arg("mask") = -1, DOC(dai, DeviceBase, setIrLaserDotProjectorIntensity)) + .def("setIrFloodLightIntensity", [](DeviceBase& d, float intensity, int mask) { py::gil_scoped_release release; return d.setIrFloodLightIntensity(intensity, mask); }, py::arg("intensity"), py::arg("mask") = -1, DOC(dai, DeviceBase, setIrFloodLightIntensity)) .def("getIrDrivers", [](DeviceBase& d) { py::gil_scoped_release release; return d.getIrDrivers(); }, DOC(dai, DeviceBase, getIrDrivers)) .def("isEepromAvailable", [](DeviceBase& d) { py::gil_scoped_release release; return d.isEepromAvailable(); }, DOC(dai, DeviceBase, isEepromAvailable)) .def("flashCalibration2", [](DeviceBase& d, CalibrationHandler ch) { py::gil_scoped_release release; return d.flashCalibration2(ch); }, DOC(dai, DeviceBase, flashCalibration2)) diff --git a/src/pipeline/CommonBindings.cpp b/src/pipeline/CommonBindings.cpp index 2b52843af..5e03660d6 100644 --- a/src/pipeline/CommonBindings.cpp +++ b/src/pipeline/CommonBindings.cpp @@ -5,6 +5,7 @@ // depthai-shared #include "depthai-shared/common/CameraBoardSocket.hpp" +#include "depthai-shared/common/ConnectionInterface.hpp" #include "depthai-shared/common/EepromData.hpp" #include "depthai-shared/common/CameraImageOrientation.hpp" #include "depthai-shared/common/CameraSensorType.hpp" @@ -40,6 +41,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ py::class_ point3f(m, "Point3f", DOC(dai, Point3f)); py::class_ size2f(m, "Size2f", DOC(dai, Size2f)); py::enum_ cameraBoardSocket(m, "CameraBoardSocket", DOC(dai, CameraBoardSocket)); + py::enum_ connectionInterface(m, "connectionInterface", DOC(dai, ConnectionInterface)); py::enum_ cameraSensorType(m, "CameraSensorType", DOC(dai, CameraSensorType)); py::enum_ cameraImageOrientation(m, "CameraImageOrientation", DOC(dai, CameraImageOrientation)); py::class_ cameraSensorConfig(m, "CameraSensorConfig", DOC(dai, CameraSensorConfig)); @@ -183,7 +185,12 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ .value("TOF", CameraSensorType::TOF) .value("THERMAL", CameraSensorType::THERMAL) ; - + // ConnectionInterface enum bindings + connectionInterface + .value("USB", ConnectionInterface::USB) + .value("ETHERNET", ConnectionInterface::ETHERNET) + .value("WIFI", ConnectionInterface::WIFI) + ; // CameraImageOrientation enum bindings cameraImageOrientation .value("AUTO", CameraImageOrientation::AUTO) diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index 839944b9f..9c716d1aa 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -29,6 +29,7 @@ #include "depthai/pipeline/node/AprilTag.hpp" #include "depthai/pipeline/node/DetectionParser.hpp" #include "depthai/pipeline/node/UVC.hpp" +#include "depthai/pipeline/node/Warp.hpp" // depthai-shared #include "depthai-shared/properties/GlobalProperties.hpp" @@ -145,6 +146,7 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){ .def("createDetectionParser", &Pipeline::create) .def("createUVC", &Pipeline::create) .def("createCamera", &Pipeline::create) + .def("createWarp", &Pipeline::create) ; diff --git a/src/pipeline/datatype/CameraControlBindings.cpp b/src/pipeline/datatype/CameraControlBindings.cpp index 06ebb4ab4..07a77d843 100644 --- a/src/pipeline/datatype/CameraControlBindings.cpp +++ b/src/pipeline/datatype/CameraControlBindings.cpp @@ -21,6 +21,8 @@ void bind_cameracontrol(pybind11::module& m, void* pCallstack){ py::enum_ rawCameraControlAutoFocusMode(rawCameraControl, "AutoFocusMode", DOC(dai, RawCameraControl, AutoFocusMode)); py::enum_ rawCameraControlAutoWhiteBalanceMode(rawCameraControl, "AutoWhiteBalanceMode", DOC(dai, RawCameraControl, AutoWhiteBalanceMode)); py::enum_ rawCameraControlSceneMode(rawCameraControl, "SceneMode", DOC(dai, RawCameraControl, SceneMode)); + py::enum_ rawCameraControlControlMode(rawCameraControl, "ControlMode", DOC(dai, RawCameraControl, ControlMode)); + py::enum_ rawCameraControlCaptureIntent(rawCameraControl, "CaptureIntent", DOC(dai, RawCameraControl, CaptureIntent)); py::enum_ rawCameraControlAntiBandingMode(rawCameraControl, "AntiBandingMode", DOC(dai, RawCameraControl, AntiBandingMode)); py::enum_ rawCameraControlEffectMode(rawCameraControl, "EffectMode", DOC(dai, RawCameraControl, EffectMode)); py::enum_ rawCameraControlFrameSyncMode(rawCameraControl, "FrameSyncMode", DOC(dai, RawCameraControl, FrameSyncMode)); @@ -125,6 +127,23 @@ std::vector camCtrlAttr; .value("BARCODE", RawCameraControl::SceneMode::BARCODE) ; + camCtrlAttr.push_back("ControlMode"); + rawCameraControlControlMode + .value("OFF", RawCameraControl::ControlMode::OFF) + .value("AUTO", RawCameraControl::ControlMode::AUTO) + .value("USE_SCENE_MODE", RawCameraControl::ControlMode::USE_SCENE_MODE) + ; + + camCtrlAttr.push_back("CaptureIntent"); + rawCameraControlCaptureIntent + .value("CUSTOM", RawCameraControl::CaptureIntent::CUSTOM) + .value("PREVIEW", RawCameraControl::CaptureIntent::PREVIEW) + .value("STILL_CAPTURE", RawCameraControl::CaptureIntent::STILL_CAPTURE) + .value("VIDEO_RECORD", RawCameraControl::CaptureIntent::VIDEO_RECORD) + .value("VIDEO_SNAPSHOT", RawCameraControl::CaptureIntent::VIDEO_SNAPSHOT) + .value("ZERO_SHUTTER_LAG", RawCameraControl::CaptureIntent::ZERO_SHUTTER_LAG) + ; + camCtrlAttr.push_back("AntiBandingMode"); rawCameraControlAntiBandingMode .value("OFF", RawCameraControl::AntiBandingMode::OFF) @@ -163,7 +182,10 @@ std::vector camCtrlAttr; .def_readwrite("awbMode", &RawCameraControl::awbMode) .def_readwrite("sceneMode", &RawCameraControl::sceneMode) .def_readwrite("antiBandingMode", &RawCameraControl::antiBandingMode) + .def_readwrite("captureIntent", &RawCameraControl::captureIntent) + .def_readwrite("controlMode", &RawCameraControl::controlMode) .def_readwrite("effectMode", &RawCameraControl::effectMode) + .def_readwrite("aeMaxExposureTimeUs", &RawCameraControl::aeMaxExposureTimeUs) .def_readwrite("aeLockMode", &RawCameraControl::aeLockMode) .def_readwrite("awbLockMode", &RawCameraControl::awbLockMode) .def_readwrite("expCompensation", &RawCameraControl::expCompensation) @@ -200,6 +222,8 @@ std::vector camCtrlAttr; .def("setAutoExposureLock", &CameraControl::setAutoExposureLock, py::arg("lock"), DOC(dai, CameraControl, setAutoExposureLock)) .def("setAutoExposureRegion", &CameraControl::setAutoExposureRegion, py::arg("startX"), py::arg("startY"), py::arg("width"), py::arg("height"), DOC(dai, CameraControl, setAutoExposureRegion)) .def("setAutoExposureCompensation", &CameraControl::setAutoExposureCompensation, py::arg("compensation"), DOC(dai, CameraControl, setAutoExposureCompensation)) + .def("setAutoExposureLimit", py::overload_cast(&CameraControl::setAutoExposureLimit), py::arg("maxExposureTimeUs"), DOC(dai, CameraControl, setAutoExposureLimit)) + .def("setAutoExposureLimit", py::overload_cast(&CameraControl::setAutoExposureLimit), py::arg("maxExposureTime"), DOC(dai, CameraControl, setAutoExposureLimit, 2)) .def("setAntiBandingMode", &CameraControl::setAntiBandingMode, py::arg("mode"), DOC(dai, CameraControl, setAntiBandingMode)) .def("setManualExposure", py::overload_cast(&CameraControl::setManualExposure), py::arg("exposureTimeUs"), py::arg("sensitivityIso"), DOC(dai, CameraControl, setManualExposure)) .def("setManualExposure", py::overload_cast(&CameraControl::setManualExposure), py::arg("exposureTime"), py::arg("sensitivityIso"), DOC(dai, CameraControl, setManualExposure, 2)) @@ -214,6 +238,8 @@ std::vector camCtrlAttr; .def("setChromaDenoise", &CameraControl::setChromaDenoise, py::arg("value"), DOC(dai, CameraControl, setChromaDenoise)) .def("setSceneMode", &CameraControl::setSceneMode, py::arg("mode"), DOC(dai, CameraControl, setSceneMode)) .def("setEffectMode", &CameraControl::setEffectMode, py::arg("mode"), DOC(dai, CameraControl, setEffectMode)) + .def("setControlMode", &CameraControl::setControlMode, py::arg("mode"), DOC(dai, CameraControl, setControlMode)) + .def("setCaptureIntent", &CameraControl::setCaptureIntent, py::arg("mode"), DOC(dai, CameraControl, setCaptureIntent)) .def("set", &CameraControl::set, py::arg("config"), DOC(dai, CameraControl, set)) // getters .def("getCaptureStill", &CameraControl::getCaptureStill, DOC(dai, CameraControl, getCaptureStill)) diff --git a/src/pipeline/datatype/EncodedFrameBindings.cpp b/src/pipeline/datatype/EncodedFrameBindings.cpp new file mode 100644 index 000000000..91bda7f1f --- /dev/null +++ b/src/pipeline/datatype/EncodedFrameBindings.cpp @@ -0,0 +1,135 @@ +#include "DatatypeBindings.hpp" +#include "depthai-shared/datatype/RawEncodedFrame.hpp" +#include "pipeline/CommonBindings.hpp" +#include +#include + +// depthai +#include "depthai/pipeline/datatype/EncodedFrame.hpp" + +// pybind +#include +#include + +void bind_encodedframe(pybind11::module &m, void *pCallstack) { + + using namespace dai; + + py::class_> + rawEncodedFrame(m, "RawEncodedFrame", DOC(dai, RawEncodedFrame)); + py::enum_ rawEncodedFrameProfile(rawEncodedFrame, + "Profile"); + py::enum_ rawEncodedFrameType( + rawEncodedFrame, "FrameType", DOC(dai, RawEncodedFrame, FrameType)); + py::class_> encodedFrame( + m, "EncodedFrame", DOC(dai, EncodedFrame)); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // Call the rest of the type defines, then perform the actual bindings + Callstack *callstack = (Callstack *)pCallstack; + auto cb = callstack->top(); + callstack->pop(); + cb(m, pCallstack); + // Actual bindings + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Metadata / raw + + rawEncodedFrame.def(py::init<>()) + .def_readwrite("quality", &RawEncodedFrame::quality) + .def_readwrite("bitrate", &RawEncodedFrame::bitrate) + .def_readwrite("profile", &RawEncodedFrame::profile) + .def_readwrite("lossless", &RawEncodedFrame::lossless) + .def_readwrite("type", &RawEncodedFrame::type) + .def_readwrite("instanceNum", &RawEncodedFrame::instanceNum) + .def_readwrite("sequenceNum", &RawEncodedFrame::sequenceNum) + .def_property( + "ts", + [](const RawEncodedFrame &o) { + double ts = o.ts.sec + o.ts.nsec / 1000000000.0; + return ts; + }, + [](RawEncodedFrame &o, double ts) { + o.ts.sec = ts; + o.ts.nsec = (ts - o.ts.sec) * 1000000000.0; + }) + .def_property( + "tsDevice", + [](const RawEncodedFrame &o) { + double ts = o.tsDevice.sec + o.tsDevice.nsec / 1000000000.0; + return ts; + }, + [](RawEncodedFrame &o, double ts) { + o.tsDevice.sec = ts; + o.tsDevice.nsec = (ts - o.tsDevice.sec) * 1000000000.0; + }); + + rawEncodedFrameProfile.value("JPEG", EncodedFrame::Profile::JPEG) + .value("AVC", EncodedFrame::Profile::AVC) + .value("HEVC", EncodedFrame::Profile::HEVC); + + rawEncodedFrameType.value("I", EncodedFrame::FrameType::I) + .value("P", EncodedFrame::FrameType::P) + .value("B", EncodedFrame::FrameType::B) + .value("Unknown", EncodedFrame::FrameType::Unknown); + + // Message + encodedFrame + .def(py::init<>()) + // getters + .def("getTimestamp", + py::overload_cast<>(&EncodedFrame::Buffer::getTimestamp, py::const_), + DOC(dai, Buffer, getTimestamp)) + .def("getTimestampDevice", + py::overload_cast<>(&EncodedFrame::Buffer::getTimestampDevice, py::const_), + DOC(dai, Buffer, getTimestampDevice)) + .def("getInstanceNum", &EncodedFrame::getInstanceNum, + DOC(dai, EncodedFrame, getInstanceNum)) + .def("getSequenceNum", &EncodedFrame::Buffer::getSequenceNum, + DOC(dai, Buffer, getSequenceNum)) + .def("getExposureTime", &EncodedFrame::getExposureTime, + DOC(dai, EncodedFrame, getExposureTime)) + .def("getSensitivity", &EncodedFrame::getSensitivity, + DOC(dai, EncodedFrame, getSensitivity)) + .def("getColorTemperature", &EncodedFrame::getColorTemperature, + DOC(dai, EncodedFrame, getColorTemperature)) + .def("getLensPosition", &EncodedFrame::getLensPosition, + DOC(dai, EncodedFrame, getLensPosition)) + .def("getQuality", &EncodedFrame::getQuality, + DOC(dai, EncodedFrame, getQuality)) + .def("getBitrate", &EncodedFrame::getBitrate, + DOC(dai, EncodedFrame, getBitrate)) + .def("getFrameType", &EncodedFrame::getFrameType, + DOC(dai, EncodedFrame, getFrameType)) + .def("getLossless", &EncodedFrame::getLossless, + DOC(dai, EncodedFrame, getLossless)) + .def("getProfile", &EncodedFrame::getProfile, + DOC(dai, EncodedFrame, getProfile)) + + // setters + .def("setTimestamp", &EncodedFrame::setTimestamp, + DOC(dai, EncodedFrame, setTimestamp)) + .def("setTimestampDevice", &EncodedFrame::setTimestampDevice, + DOC(dai, EncodedFrame, setTimestampDevice)) + .def("setSequenceNum", &EncodedFrame::setSequenceNum, + DOC(dai, EncodedFrame, setSequenceNum)) + .def("setQuality", &EncodedFrame::setQuality, + DOC(dai, EncodedFrame, getQuality)) + .def("setBitrate", &EncodedFrame::setBitrate, + DOC(dai, EncodedFrame, getBitrate)) + .def("setFrameType", &EncodedFrame::setFrameType, + DOC(dai, EncodedFrame, getFrameType)) + .def("setLossless", &EncodedFrame::setLossless, + DOC(dai, EncodedFrame, getLossless)) + .def("setProfile", &EncodedFrame::setProfile, + DOC(dai, EncodedFrame, getProfile)); + // add aliases dai.ImgFrame.Type and dai.ImgFrame.Specs + m.attr("EncodedFrame").attr("FrameType") = + m.attr("RawEncodedFrame").attr("FrameType"); + m.attr("EncodedFrame").attr("Profile") = + m.attr("RawEncodedFrame").attr("Profile"); +} diff --git a/src/pipeline/datatype/MessageGroupBindings.cpp b/src/pipeline/datatype/MessageGroupBindings.cpp new file mode 100644 index 000000000..a77c5fbd5 --- /dev/null +++ b/src/pipeline/datatype/MessageGroupBindings.cpp @@ -0,0 +1,65 @@ +#include "DatatypeBindings.hpp" +#include "depthai-shared/datatype/RawMessageGroup.hpp" +#include "pipeline/CommonBindings.hpp" +#include +#include + +// depthai +#include "depthai/pipeline/datatype/MessageGroup.hpp" + +//pybind +#include +#include + +// #include "spdlog/spdlog.h" + +void bind_message_group(pybind11::module& m, void* pCallstack){ + + using namespace dai; + + py::class_> rawMessageGroup(m, "RawMessageGroup", DOC(dai, RawMessageGroup)); + py::class_> messageGroup(m, "MessageGroup", DOC(dai, MessageGroup)); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // Call the rest of the type defines, then perform the actual bindings + Callstack* callstack = (Callstack*) pCallstack; + auto cb = callstack->top(); + callstack->pop(); + cb(m, pCallstack); + // Actual bindings + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Metadata / raw + rawMessageGroup + .def(py::init<>()) + .def_readwrite("group", &RawMessageGroup::group) + ; + + // Message + messageGroup + .def(py::init<>()) + .def("__getitem__", [](MessageGroup& msg, const std::string& name) { + return msg[name]; + }) + .def("__setitem__", [](MessageGroup& msg, const std::string& name, std::shared_ptr data) { + return msg.add(name, data); + }) + .def("__iter__", [](MessageGroup& msg) { return py::make_iterator(msg.begin(), msg.end()); }, + py::keep_alive<0, 1>() /* Essential: keep object alive while iterator exists */) + .def("isSynced", &MessageGroup::isSynced, DOC(dai, MessageGroup, isSynced)) + .def("getIntervalNs", &MessageGroup::getIntervalNs, DOC(dai, MessageGroup, getIntervalNs)) + .def("getNumMessages", &MessageGroup::getNumMessages, DOC(dai, MessageGroup, getNumMessages)) + .def("getMessageNames", &MessageGroup::getMessageNames, DOC(dai, MessageGroup, getMessageNames)) + .def("getTimestamp", &MessageGroup::Buffer::getTimestamp, DOC(dai, Buffer, getTimestamp)) + .def("getTimestampDevice", &MessageGroup::Buffer::getTimestampDevice, DOC(dai, Buffer, getTimestampDevice)) + .def("getSequenceNum", &MessageGroup::Buffer::getSequenceNum, DOC(dai, Buffer, getSequenceNum)) + .def("setTimestamp", &MessageGroup::setTimestamp, DOC(dai, MessageGroup, setTimestamp)) + .def("setTimestampDevice", &MessageGroup::setTimestampDevice, DOC(dai, MessageGroup, setTimestampDevice)) + .def("setSequenceNum", &MessageGroup::setSequenceNum, DOC(dai, MessageGroup, setSequenceNum)) + ; + +} diff --git a/src/pipeline/node/MessageDemuxBindings.cpp b/src/pipeline/node/MessageDemuxBindings.cpp new file mode 100644 index 000000000..84f83aaf8 --- /dev/null +++ b/src/pipeline/node/MessageDemuxBindings.cpp @@ -0,0 +1,42 @@ +#include "Common.hpp" +#include "NodeBindings.hpp" + +#include "depthai-shared/properties/MessageDemuxProperties.hpp" +#include "depthai/pipeline/Node.hpp" +#include "depthai/pipeline/Pipeline.hpp" +#include "depthai/pipeline/node/MessageDemux.hpp" + +void bind_messagedemux(pybind11::module &m, void *pCallstack) { + + using namespace dai; + using namespace dai::node; + + // Node and Properties declare upfront + py::class_ messageDemuxProperties( + m, "MessageDemuxProperties", DOC(dai, MessageDemuxProperties)); + auto messageDemux = ADD_NODE(MessageDemux); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // Call the rest of the type defines, then perform the actual bindings + Callstack *callstack = (Callstack *)pCallstack; + auto cb = callstack->top(); + callstack->pop(); + cb(m, pCallstack); + // Actual bindings + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Properties + + // Node + messageDemux + .def_readonly("outputs", &MessageDemux::outputs, + DOC(dai, node, MessageDemux, outputs)) + .def_readonly("input", &MessageDemux::input, + DOC(dai, node, MessageDemux, input)); + daiNodeModule.attr("MessageDemux").attr("Properties") = + messageDemuxProperties; +} diff --git a/src/pipeline/node/NodeBindings.cpp b/src/pipeline/node/NodeBindings.cpp index 06e790377..72eb93356 100644 --- a/src/pipeline/node/NodeBindings.cpp +++ b/src/pipeline/node/NodeBindings.cpp @@ -116,6 +116,8 @@ void bind_apriltag(pybind11::module& m, void* pCallstack); void bind_detectionparser(pybind11::module& m, void* pCallstack); void bind_uvc(pybind11::module& m, void* pCallstack); void bind_tof(pybind11::module& m, void* pCallstack); +void bind_sync(pybind11::module& m, void* pCallstack); +void bind_messagedemux(pybind11::module& m, void* pCallstack); void NodeBindings::addToCallstack(std::deque& callstack) { // Bind Node et al @@ -147,6 +149,8 @@ void NodeBindings::addToCallstack(std::deque& callstack) { callstack.push_front(bind_detectionparser); callstack.push_front(bind_uvc); callstack.push_front(bind_tof); + callstack.push_front(bind_sync); + callstack.push_front(bind_messagedemux); } void NodeBindings::bind(pybind11::module& m, void* pCallstack){ diff --git a/src/pipeline/node/SyncBindings.cpp b/src/pipeline/node/SyncBindings.cpp new file mode 100644 index 000000000..10f384d5a --- /dev/null +++ b/src/pipeline/node/SyncBindings.cpp @@ -0,0 +1,48 @@ +#include "NodeBindings.hpp" +#include "Common.hpp" + +#include "depthai-shared/properties/SyncProperties.hpp" +#include "depthai/pipeline/Pipeline.hpp" +#include "depthai/pipeline/Node.hpp" +#include "depthai/pipeline/node/Sync.hpp" + +void bind_sync(pybind11::module& m, void* pCallstack){ + + using namespace dai; + using namespace dai::node; + + // Node and Properties declare upfront + py::class_ syncProperties(m, "SyncProperties", DOC(dai, SyncProperties)); + auto sync = ADD_NODE(Sync); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // Call the rest of the type defines, then perform the actual bindings + Callstack* callstack = (Callstack*) pCallstack; + auto cb = callstack->top(); + callstack->pop(); + cb(m, pCallstack); + // Actual bindings + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Properties + syncProperties + .def_readwrite("syncThresholdNs", &SyncProperties::syncThresholdNs) + .def_readwrite("syncAttempts", &SyncProperties::syncAttempts) + ; + + // Node + sync + .def_readonly("out", &Sync::out, DOC(dai, node, Sync, out)) + .def_readonly("inputs", &Sync::inputs, DOC(dai, node, Sync, inputs)) + .def("setSyncThreshold", &Sync::setSyncThreshold, py::arg("syncThreshold"), DOC(dai, node, Sync, setSyncThreshold)) + .def("setSyncAttempts", &Sync::setSyncAttempts, py::arg("maxDataSize"), DOC(dai, node, Sync, setSyncAttempts)) + .def("getSyncThreshold", &Sync::getSyncThreshold, DOC(dai, node, Sync, getSyncThreshold)) + .def("getSyncAttempts", &Sync::getSyncAttempts, DOC(dai, node, Sync, getSyncAttempts)) + ; + daiNodeModule.attr("Sync").attr("Properties") = syncProperties; + +} diff --git a/src/pipeline/node/VideoEncoderBindings.cpp b/src/pipeline/node/VideoEncoderBindings.cpp index 4f2045b64..db9e3a860 100644 --- a/src/pipeline/node/VideoEncoderBindings.cpp +++ b/src/pipeline/node/VideoEncoderBindings.cpp @@ -59,6 +59,7 @@ void bind_videoencoder(pybind11::module& m, void* pCallstack){ videoEncoder .def_readonly("input", &VideoEncoder::input, DOC(dai, node, VideoEncoder, input), DOC(dai, node, VideoEncoder, input)) .def_readonly("bitstream", &VideoEncoder::bitstream, DOC(dai, node, VideoEncoder, bitstream), DOC(dai, node, VideoEncoder, bitstream)) + .def_readonly("out", &VideoEncoder::out, DOC(dai, node, VideoEncoder, out), DOC(dai, node, VideoEncoder, out)) .def("setDefaultProfilePreset", static_cast(&VideoEncoder::setDefaultProfilePreset), py::arg("fps"), py::arg("profile"), DOC(dai, node, VideoEncoder, setDefaultProfilePreset)) .def("setDefaultProfilePreset", [](VideoEncoder& v, int width, int height, float fps, VideoEncoderProperties::Profile profile){ PyErr_WarnEx(PyExc_DeprecationWarning, "Input width/height no longer needed, automatically determined from first frame", 1); diff --git a/src/py_bindings.cpp b/src/py_bindings.cpp index e6db7796f..864704a74 100644 --- a/src/py_bindings.cpp +++ b/src/py_bindings.cpp @@ -82,9 +82,33 @@ PYBIND11_MODULE(depthai, m) // ignore } + // Apply JavaVM pointer + std::string javavmEnvStr; + constexpr static const char* javavmEnvKey = "DEPTHAI_LIBUSB_ANDROID_JAVAVM"; + try { + auto sysModule = py::module_::import("sys"); + if(py::hasattr(sysModule, javavmEnvKey)){ + javavmEnvStr = sysModule.attr(javavmEnvKey).cast(); + } + } catch (...) { + // ignore + } + try { + auto builtinsModule = py::module_::import("builtins"); + if(py::hasattr(builtinsModule, javavmEnvKey)){ + javavmEnvStr = builtinsModule.attr(javavmEnvKey).cast(); + } + } catch (...){ + // ignore + } + // JNIEnv handling + void* javavm = nullptr; + // Read the uintptr_t value from the decimal string + sscanf(javavmEnvStr.c_str(), "%" SCNuPTR, reinterpret_cast(&javavm)); + // Call dai::initialize on 'import depthai' to initialize asap with additional information to print try { - dai::initialize(std::string("Python bindings - version: ") + DEPTHAI_PYTHON_VERSION + " from " + DEPTHAI_PYTHON_COMMIT_DATETIME + " build: " + DEPTHAI_PYTHON_BUILD_DATETIME, installSignalHandler); + dai::initialize(std::string("Python bindings - version: ") + DEPTHAI_PYTHON_VERSION + " from " + DEPTHAI_PYTHON_COMMIT_DATETIME + " build: " + DEPTHAI_PYTHON_BUILD_DATETIME, installSignalHandler, javavm); } catch (const std::exception&) { // ignore, will be initialized later on if possible } diff --git a/tests/multithread.py b/tests/multithread.py new file mode 100644 index 000000000..6252527aa --- /dev/null +++ b/tests/multithread.py @@ -0,0 +1,46 @@ +# TODO: increase defaults in depthai! Below is a workaround for this issue on some setups: +# Failed to find device after booting, error message: X_LINK_DEVICE_NOT_FOUND +# If this error is still observed, might be a FW crash on initialization +if 1: + import os + os.environ["DEPTHAI_WATCHDOG_INITIAL_DELAY"] = "40000" + os.environ["DEPTHAI_BOOTUP_TIMEOUT"] = "40000" + +import depthai as dai +import threading +import traceback +import time +import os + +def worker(devinfo, id): + print(f'[{id}] opening bootloader...') + try: + with dai.DeviceBootloader(devinfo) as bl: + print(f'[{id}] bootloader version: {bl.getVersion()}') + with dai.Device(devinfo) as dev: + print(f'[{id}] device started, name: {dev.getDeviceName()}') + time.sleep(6) + # Exceptions aren't propagated, so simply exit the app with an error + except Exception as e: + print(f'[{id}] FAILED: {e}') + traceback.print_exc() + os._exit(-1) + +device_infos = dai.Device.getAllAvailableDevices() +n = len(device_infos) +if n <= 0: + print('No devices found!') + os._exit(-1) +print(f'Found {n} devices, handling each in a thread...') +threads = [] +for devinfo in device_infos: + id = devinfo.name # IP address for PoE + t = threading.Thread(target=worker, args=(devinfo, id, )) + t.name += f'-{id}' # Thread name useful for debugging + t.start() + threads.append(t) + +for t in threads: + t.join() + +print('Multi-threading test succeeded!') diff --git a/utilities/cam_test.py b/utilities/cam_test.py index eabd9cfb5..1f47523a9 100755 --- a/utilities/cam_test.py +++ b/utilities/cam_test.py @@ -24,6 +24,9 @@ '0' - Select control: sharpness '[' - Select control: luma denoise ']' - Select control: chroma denoise +'\' - Select control: scene mode +';' - Select control: control mode +''' - Select control: capture intent 'a' 'd' - Increase/decrease dot projector intensity 'w' 's' - Increase/decrease flood LED intensity @@ -93,6 +96,8 @@ def socket_type_pair(arg): help="ToF median filter kernel size") parser.add_argument('-rgbprev', '--rgb-preview', action='store_true', help="Show RGB `preview` stream instead of full size `isp`") +parser.add_argument('-show', '--show-meta', action='store_true', + help="List frame metadata (seqno, timestamp, exp, iso etc). Can also toggle with `\`") parser.add_argument('-d', '--device', default="", type=str, help="Optional MX ID of the device to connect to.") @@ -189,6 +194,22 @@ def update(self, timestamp=None): def get(self): return self.fps +class Cycle: + def __init__(self, enum_type, start_item=None): + self.items = [item for name, item in vars(enum_type).items() if name.isupper()] + # If start_item is provided, set the index to its position. Otherwise, default to 0 + self.index = self.items.index(start_item) if start_item else 0 + + def step(self, n): + self.index = (self.index + n) % len(self.items) + return self.items[self.index] + + def next(self): + return self.step(1) + + def prev(self): + return self.step(-1) + # Start defining a pipeline pipeline = dai.Pipeline() # Uncomment to get better throughput @@ -264,6 +285,7 @@ def get(self): # cam[c].initialControl.setManualExposure(15000, 400) # exposure [us], iso # When set, takes effect after the first 2 frames # cam[c].initialControl.setManualWhiteBalance(4000) # light temperature in K, 1000..12000 + # cam[c].initialControl.setAutoExposureLimit(5000) # can also be updated at runtime control.out.link(cam[c].inputControl) if rotate[c]: cam[c].setImageOrientation(dai.CameraImageOrientation.ROTATE_180_DEG) @@ -333,10 +355,10 @@ def exit_cleanly(signum, frame): EXP_STEP = 500 # us ISO_STEP = 50 LENS_STEP = 3 - DOT_STEP = 100 - FLOOD_STEP = 100 - DOT_MAX = 1200 - FLOOD_MAX = 1500 + DOT_STEP = 0.05 + FLOOD_STEP = 0.05 + DOT_MAX = 1 + FLOOD_MAX = 1 # Defaults and limits for manual focus/exposure controls lensPos = 150 @@ -354,12 +376,12 @@ def exit_cleanly(signum, frame): dotIntensity = 0 floodIntensity = 0 - awb_mode = cycle([item for name, item in vars( - dai.CameraControl.AutoWhiteBalanceMode).items() if name.isupper()]) - anti_banding_mode = cycle([item for name, item in vars( - dai.CameraControl.AntiBandingMode).items() if name.isupper()]) - effect_mode = cycle([item for name, item in vars( - dai.CameraControl.EffectMode).items() if name.isupper()]) + awb_mode = Cycle(dai.CameraControl.AutoWhiteBalanceMode) + anti_banding_mode = Cycle(dai.CameraControl.AntiBandingMode) + effect_mode = Cycle(dai.CameraControl.EffectMode) + scene_mode = Cycle(dai.CameraControl.SceneMode) + control_mode = Cycle(dai.CameraControl.ControlMode) + capture_intent = Cycle(dai.CameraControl.CaptureIntent) ae_comp = 0 ae_lock = False @@ -371,7 +393,7 @@ def exit_cleanly(signum, frame): luma_denoise = 0 chroma_denoise = 0 control = 'none' - show = False + show = args.show_meta jet_custom = cv2.applyColorMap(np.arange(256, dtype=np.uint8), cv2.COLORMAP_JET) jet_custom[0] = [0, 0, 0] @@ -402,7 +424,7 @@ def exit_cleanly(signum, frame): frame = cv2.normalize(frame, frame, alpha=255, beta=0, norm_type=cv2.NORM_MINMAX, dtype=cv2.CV_8U) frame = cv2.applyColorMap(frame, jet_custom) if show: - txt = f"[{c:5}, {pkt.getSequenceNum():4}] " + txt = f"[{c:5}, {pkt.getSequenceNum():4}, {pkt.getTimestamp().total_seconds():.6f}] " txt += f"Exp: {pkt.getExposureTime().total_seconds()*1000:6.3f} ms, " txt += f"ISO: {pkt.getSensitivity():4}, " txt += f"Lens pos: {pkt.getLensPosition():3}, " @@ -415,10 +437,11 @@ def exit_cleanly(signum, frame): if capture: capture_file_info = ('capture_' + c + '_' + cam_name[cam_socket_opts[cam_skt].name] + '_' + str(width) + 'x' + str(height) + + '_' + capture_time + '_exp_' + str(int(pkt.getExposureTime().total_seconds()*1e6)) + '_iso_' + str(pkt.getSensitivity()) + '_lens_' + str(pkt.getLensPosition()) - + '_' + capture_time + + '_' + str(pkt.getColorTemperature()) + 'K' + '_' + str(pkt.getSequenceNum()) ) capture_list.remove(c) @@ -534,23 +557,27 @@ def exit_cleanly(signum, frame): dotIntensity = dotIntensity - DOT_STEP if dotIntensity < 0: dotIntensity = 0 - device.setIrLaserDotProjectorBrightness(dotIntensity) + device.setIrLaserDotProjectorIntensity(dotIntensity) + print(f'IR Dot intensity:', dotIntensity) elif key == ord('d'): dotIntensity = dotIntensity + DOT_STEP if dotIntensity > DOT_MAX: dotIntensity = DOT_MAX - device.setIrLaserDotProjectorBrightness(dotIntensity) + device.setIrLaserDotProjectorIntensity(dotIntensity) + print(f'IR Dot intensity:', dotIntensity) elif key == ord('w'): floodIntensity = floodIntensity + FLOOD_STEP if floodIntensity > FLOOD_MAX: floodIntensity = FLOOD_MAX - device.setIrFloodLightBrightness(floodIntensity) + device.setIrFloodLightIntensity(floodIntensity) + print(f'IR Flood intensity:', floodIntensity) elif key == ord('s'): floodIntensity = floodIntensity - FLOOD_STEP if floodIntensity < 0: floodIntensity = 0 - device.setIrFloodLightBrightness(floodIntensity) - elif key >= 0 and chr(key) in '34567890[]p': + device.setIrFloodLightIntensity(floodIntensity) + print(f'IR Flood intensity:', floodIntensity) + elif key >= 0 and chr(key) in '34567890[]p\\;\'': if key == ord('3'): control = 'awb_mode' elif key == ord('4'): @@ -567,6 +594,12 @@ def exit_cleanly(signum, frame): control = 'saturation' elif key == ord('0'): control = 'sharpness' + elif key == ord('\\'): + control = 'scene_mode' + elif key == ord(';'): + control = 'control_mode' + elif key == ord('\''): + control = 'capture_intent' elif key == ord('['): control = 'luma_denoise' elif key == ord(']'): @@ -582,23 +615,35 @@ def exit_cleanly(signum, frame): change = 1 ctrl = dai.CameraControl() if control == 'none': - print("Please select a control first using keys 3..9 0 [ ]") + print("Please select a control first using keys 3..9 0 [ ] \\ ; \'") elif control == 'ae_comp': ae_comp = clamp(ae_comp + change, -9, 9) print("Auto exposure compensation:", ae_comp) ctrl.setAutoExposureCompensation(ae_comp) elif control == 'anti_banding_mode': - abm = next(anti_banding_mode) + abm = anti_banding_mode.step(change) print("Anti-banding mode:", abm) ctrl.setAntiBandingMode(abm) elif control == 'awb_mode': - awb = next(awb_mode) + awb = awb_mode.step(change) print("Auto white balance mode:", awb) ctrl.setAutoWhiteBalanceMode(awb) elif control == 'effect_mode': - eff = next(effect_mode) + eff = effect_mode.step(change) print("Effect mode:", eff) ctrl.setEffectMode(eff) + elif control == 'scene_mode': + sc = scene_mode.step(change) + print("Scene mode:", sc) + ctrl.setSceneMode(sc) + elif control == 'control_mode': + cm = control_mode.step(change) + print("Control mode:", cm) + ctrl.setControlMode(cm) + elif control == 'capture_intent': + ci = capture_intent.step(change) + print("Capture intent:", ci) + ctrl.setCaptureIntent(ci) elif control == 'brightness': brightness = clamp(brightness + change, -10, 10) print("Brightness:", brightness)