diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index f74300ab0..396b38b5b 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -1,7 +1,7 @@ -# Temporary pybind11 2.6.3dev1 chrono bindings patch +# Pybind11 2.7.0 hunter_config( pybind11 - VERSION "2.6.3dev1" - URL "https://github.com/pybind/pybind11/archive/54430436fee2afc4f8443691075a6208f9ea8eba.tar.gz" - SHA1 "c8550f7d77e92045c996d17f1d214223d1e2e620" + VERSION "2.7.0" + URL "https://github.com/pybind/pybind11/archive/refs/tags/v2.7.0.tar.gz" + SHA1 "3a7010e5952c56e08c8f9b7d6fb458a173fd585a" ) diff --git a/cmake/pybind11-mkdoc.cmake b/cmake/pybind11-mkdoc.cmake index 2a9b7425a..271926d08 100644 --- a/cmake/pybind11-mkdoc.cmake +++ b/cmake/pybind11-mkdoc.cmake @@ -56,6 +56,8 @@ function(pybind11_mkdoc_setup_internal target output_path mkdoc_headers enforce) # Docstring wrap width -w 80 -o "${output_path}" + # C++ standard + -std=c++14 # List of include directories "-I$,;-I>" # List of compiler definitions diff --git a/depthai-core b/depthai-core index 7d76a830f..22233219b 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 7d76a830ffc51512adae455ec28b1150eabec513 +Subproject commit 22233219b50f4918fe9cbb4c0c0ec232383eb78f diff --git a/docs/source/components/bootloader.rst b/docs/source/components/bootloader.rst index b7a58c87c..a318184a5 100644 --- a/docs/source/components/bootloader.rst +++ b/docs/source/components/bootloader.rst @@ -36,6 +36,8 @@ or update the bootloader itself. progressCb parameter takes a callback function, which will be called each time an progress update occurs (rate limited to 1 second). This is mainly used to inform the user of the current flashing progress. +You can also check the version of the current bootloader by using the :ref:`Bootloader Version` example. + DepthAI Application Package (.dap) ################################## diff --git a/docs/source/components/nodes/color_camera.rst b/docs/source/components/nodes/color_camera.rst index 94b5faec8..961e2b245 100644 --- a/docs/source/components/nodes/color_camera.rst +++ b/docs/source/components/nodes/color_camera.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - cam = pipeline.createColorCamera() + cam = pipeline.create(dai.node.ColorCamera) .. code-tab:: c++ @@ -67,7 +67,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - cam = pipeline.createColorCamera() + cam = pipeline.create(dai.node.ColorCamera) cam.setPreviewSize(300, 300) cam.setBoardSocket(dai.CameraBoardSocket.RGB) cam.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P) @@ -98,7 +98,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.ColorCamera + .. autoclass:: depthai.node.ColorCamera :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/edge_detector.rst b/docs/source/components/nodes/edge_detector.rst index 6c30c0528..d847de9e0 100644 --- a/docs/source/components/nodes/edge_detector.rst +++ b/docs/source/components/nodes/edge_detector.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - edgeDetector = pipeline.createEdgeDetector() + edgeDetector = pipeline.create(dai.node.EdgeDetector) .. code-tab:: c++ @@ -48,7 +48,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - edgeDetector = pipeline.createEdgeDetector() + edgeDetector = pipeline.create(dai.node.EdgeDetector) sobelHorizontalKernel = [[1, 0, -1], [2, 0, -2], [1, 0, -1]] sobelVerticalKernel = [[1, 2, 1], [0, 0, 0], [-1, -2, -1]] @@ -75,7 +75,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.EdgeDetector + .. autoclass:: depthai.node.EdgeDetector :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/image_manip.rst b/docs/source/components/nodes/image_manip.rst index cac18e7ca..ea2c9ed48 100644 --- a/docs/source/components/nodes/image_manip.rst +++ b/docs/source/components/nodes/image_manip.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - manip = pipeline.createImageManip() + manip = pipeline.create(dai.node.ImageManip) .. code-tab:: c++ @@ -52,7 +52,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - manip = pipeline.createImageManip() + manip = pipeline.create(dai.node.ImageManip) manip.initialConfig.setResize(300, 300) manip.initialConfig.setFrameType(dai.ImgFrame.Type.BGR888p) @@ -95,7 +95,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.ImageManip + .. autoclass:: depthai.node.ImageManip :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/mobilenet_detection_network.rst b/docs/source/components/nodes/mobilenet_detection_network.rst index cd84e8d51..9e85d7d7f 100644 --- a/docs/source/components/nodes/mobilenet_detection_network.rst +++ b/docs/source/components/nodes/mobilenet_detection_network.rst @@ -13,7 +13,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - mobilenetDet = pipeline.createMobileNetDetectionNetwork() + mobilenetDet = pipeline.create(dai.node.MobileNetDetectionNetwork) .. code-tab:: c++ @@ -50,7 +50,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - mobilenetDet = pipeline.createMobileNetDetectionNetwork() + mobilenetDet = pipeline.create(dai.node.MobileNetDetectionNetwork) mobilenetDet.setConfidenceThreshold(0.5) mobilenetDet.setBlobPath(nnBlobPath) @@ -81,7 +81,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.MobileNetDetectionNetwork + .. autoclass:: depthai.node.MobileNetDetectionNetwork :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/mobilenet_spatial_detection_network.rst.rst b/docs/source/components/nodes/mobilenet_spatial_detection_network.rst.rst index e5eae65f6..5f994aa94 100644 --- a/docs/source/components/nodes/mobilenet_spatial_detection_network.rst.rst +++ b/docs/source/components/nodes/mobilenet_spatial_detection_network.rst.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - mobilenetSpatial = pipeline.createMobileNetSpatialDetectionNetwork() + mobilenetSpatial = pipeline.create(dai.node.MobileNetSpatialDetectionNetwork) .. code-tab:: c++ @@ -52,7 +52,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - mobilenetSpatial = pipeline.createMobileNetSpatialDetectionNetwork() + mobilenetSpatial = pipeline.create(dai.node.MobileNetSpatialDetectionNetwork) mobilenetSpatial.setBlobPath(nnBlobPath) # Will ingore all detections whose confidence is below 50% @@ -98,7 +98,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.MobileNetSpatialDetectionNetwork + .. autoclass:: depthai.node.MobileNetSpatialDetectionNetwork :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/mono_camera.rst b/docs/source/components/nodes/mono_camera.rst index 67b64b7ae..c8d440e7b 100644 --- a/docs/source/components/nodes/mono_camera.rst +++ b/docs/source/components/nodes/mono_camera.rst @@ -12,7 +12,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - mono = pipeline.createMonoCamera() + mono = pipeline.create(dai.node.MonoCamera) .. code-tab:: c++ @@ -48,7 +48,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - mono = pipeline.createMonoCamera() + mono = pipeline.create(dai.node.MonoCamera) mono.setBoardSocket(dai.CameraBoardSocket.RIGHT) mono.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) @@ -73,7 +73,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.MonoCamera + .. autoclass:: depthai.node.MonoCamera :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/neural_network.rst b/docs/source/components/nodes/neural_network.rst index a7c1596f9..d7e0256f0 100644 --- a/docs/source/components/nodes/neural_network.rst +++ b/docs/source/components/nodes/neural_network.rst @@ -13,7 +13,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - nn = pipeline.createNeuralNetwork() + nn = pipeline.create(dai.node.NeuralNetwork) .. code-tab:: c++ @@ -60,12 +60,12 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - nn = pipeline.createNeuralNetwork() + nn = pipeline.create(dai.node.NeuralNetwork) nn.setBlobPath(bbBlobPath) cam.out.link(nn.input) # Send NN out to the host via XLink - nnXout = pipeline.createXLinkOut() + nnXout = pipeline.create(dai.node.XLinkOut) nnXout.setStreamName("nn") nn.out.link(nnXout.input) @@ -124,7 +124,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.NeuralNetwork + .. autoclass:: depthai.node.NeuralNetwork :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/object_tracker.rst b/docs/source/components/nodes/object_tracker.rst index a90ed2816..644cd924f 100644 --- a/docs/source/components/nodes/object_tracker.rst +++ b/docs/source/components/nodes/object_tracker.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - objectTracker = pipeline.createObjectTracker() + objectTracker = pipeline.create(dai.node.ObjectTracker) .. code-tab:: c++ @@ -53,7 +53,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - objectTracker = pipeline.createObjectTracker() + objectTracker = pipeline.create(dai.node.ObjectTracker) objectTracker.setDetectionLabelsToTrack([15]) # Track only person # Possible tracking types: ZERO_TERM_COLOR_HISTOGRAM, ZERO_TERM_IMAGELESS @@ -92,7 +92,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.ObjectTracker + .. autoclass:: depthai.node.ObjectTracker :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/script.rst b/docs/source/components/nodes/script.rst new file mode 100644 index 000000000..1e8bc1f0a --- /dev/null +++ b/docs/source/components/nodes/script.rst @@ -0,0 +1,148 @@ +Script +====== + +Script node allows users to run **custom Python scripts on the device**. Due to the computational resource constraints, +script node shouldn't be used for heavy computing (eg. image manipulation/CV), but for managing the flow +of the pipeline. Example use cases would be controlling nodes like :ref:`ImageManip`, :ref:`ColorCamera`, :ref:`SpatialLocationCalculator`, +decoding :ref:`NeuralNetwork` results, or interfacing with GPIOs. + +How to place it +############### + +.. tabs:: + + .. code-tab:: py + + pipeline = dai.Pipeline() + script = pipeline.create(dai.node.Script) + + .. code-tab:: c++ + + dai::Pipeline pipeline; + auto script = pipeline.create(); + + +Inputs and Outputs +################## + +.. code-block:: + + inputs[] ┌──────────────┐ outputs[] + ---------►│ ├-----------► + ---------►│ ├-----------► + ... │ Script | ... + ... │ │ ... + ---------►│ ├-----------► + └──────────────┘ + +Users can define as many inputs and outputs as they need. Inputs and outputs can be any :ref:`Message ` type. + +Usage +##### + +.. tabs:: + + .. code-tab:: py + + script = pipeline.create(dai.node.Script) + script.setScript(""" + import time + import marshal + num = 123 + node.warn(f"Number {num}") # Print to host + x = [1, "Hello", {"Foo": "Bar"}] + x_serial = marshal.dumps(x) + b = Buffer(len(x_serial)) + while True: + time.sleep(1) + b.getData()[:] = x_serial + node.io['out'].send(b) + """) + script.outputs['out'].link(xout.input) + + # ... + # After initializing the device, enable log levels + device.setLogLevel(dai.LogLevel.WARN) + device.setLogOutputLevel(dai.LogLevel.WARN) + + .. code-tab:: c++ + + auto script = pipeline.create(); + script->setScript(R"( + import time + import marshal + num = 123 + node.warn(f"Number {num}") # Print to host + x = [1, "Hello", {"Foo": "Bar"}] + x_serial = marshal.dumps(x) + b = Buffer(len(x_serial)) + while True: + time.sleep(1) + b.getData()[:] = x_serial + node.io['out'].send(b) + )"); + script->outputs["out"].link(xout->input); + + // ... + // After initializing the device, enable log levels + device.setLogLevel(dai::LogLevel.WARN); + device.setLogOutputLevel(dai::LogLevel.WARN); + +Interfacing with GPIOs +###################### + +In the script node you can interface with GPIOs of the VPU. Currently supported functions are: + +.. code-block:: python + + import GPIO # module + GPIO.read(pin) + GPIO.write(pin, value) + GPIO.setPwm(pin, highCount, lowCount, repeat=0) # repeat == 0 means indefinite + GPIO.enablePwm(pin, enable) + +Using DepthAI :ref:`Messages ` +################################################### + +The depthai module is implicitly imported to the script node. You can create new +depthai messages and assign data to it, for example: + +.. code-block:: python + + buf = Buffer(100) # Assign 100 bytes to the Buffer message + + # Create CameraControl message, set manual focus + control = CameraControl() + control.setManualFocus(100) + + imgFrame = ImgFrame(300*300*3) # Buffer with 300x300x3 bytes + + +Examples of functionality +######################### + +- :ref:`Script camera control` +- `Triangulation experiment `__ +- `Movenet decoding (edge mode) `__ - A bit more complex example by geaxgx + +Reference +######### + +.. tabs:: + + .. tab:: Python + + .. autoclass:: depthai.node.Script + :members: + :inherited-members: + :noindex: + + .. tab:: C++ + + .. doxygenclass:: dai::node::Script + :project: depthai-core + :members: + :private-members: + :undoc-members: + +.. include:: ../../includes/footer-short.rst diff --git a/docs/source/components/nodes/spatial_location_calculator.rst b/docs/source/components/nodes/spatial_location_calculator.rst index bf920a71f..6024652c9 100644 --- a/docs/source/components/nodes/spatial_location_calculator.rst +++ b/docs/source/components/nodes/spatial_location_calculator.rst @@ -98,7 +98,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.SpatialLocationCalculator + .. autoclass:: depthai.node.SpatialLocationCalculator :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/spi_out.rst b/docs/source/components/nodes/spi_out.rst index 75cd62381..d937bb660 100644 --- a/docs/source/components/nodes/spi_out.rst +++ b/docs/source/components/nodes/spi_out.rst @@ -13,7 +13,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - spi = pipeline.createSPIOut() + spi = pipeline.create(dai.node.SPIOut) .. code-tab:: c++ @@ -46,7 +46,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - spi = pipeline.createSPIOut() + spi = pipeline.create(dai.node.SPIOut) spi.setStreamName("spimetaout") spi.setBusId(0) @@ -72,7 +72,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.SPIOut + .. autoclass:: depthai.node.SPIOut :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/stereo_depth.rst b/docs/source/components/nodes/stereo_depth.rst index 98f142659..177dbd2be 100644 --- a/docs/source/components/nodes/stereo_depth.rst +++ b/docs/source/components/nodes/stereo_depth.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - stereo = pipeline.createStereoDepth() + stereo = pipeline.create(dai.node.StereoDepth) .. code-tab:: c++ @@ -127,7 +127,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - stereo = pipeline.createStereoDepth() + stereo = pipeline.create(dai.node.StereoDepth) # Better handling for occlusions: stereo.setLeftRightCheck(False) @@ -170,7 +170,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.StereoDepth + .. autoclass:: depthai.node.StereoDepth :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/system_logger.rst b/docs/source/components/nodes/system_logger.rst index 2724d419a..9dcd99834 100644 --- a/docs/source/components/nodes/system_logger.rst +++ b/docs/source/components/nodes/system_logger.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - logger = pipeline.createSystemLogger() + logger = pipeline.create(dai.node.SystemLogger) .. code-tab:: c++ @@ -44,11 +44,11 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - logger = pipeline.createSystemLogger() + logger = pipeline.create(dai.node.SystemLogger) logger.setRate(1) # 1 Hz # Send system info to the host via XLink - xout = pipeline.createXLinkOut() + xout = pipeline.create(dai.node.XLinkOut) xout.setStreamName("sysinfo") logger.out.link(xout.input) @@ -76,7 +76,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.SystemLogger + .. autoclass:: depthai.node.SystemLogger :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/video_encoder.rst b/docs/source/components/nodes/video_encoder.rst index 00d98fc6c..637897d92 100644 --- a/docs/source/components/nodes/video_encoder.rst +++ b/docs/source/components/nodes/video_encoder.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - encoder = pipeline.createVideoEncoder() + encoder = pipeline.create(dai.node.VideoEncoder) .. code-tab:: c++ @@ -48,11 +48,11 @@ Usage # Create ColorCamera beforehand # Set H265 encoding for the ColorCamera video output - videoEncoder = pipeline.createVideoEncoder() + videoEncoder = pipeline.create(dai.node.VideoEncoder) videoEncoder.setDefaultProfilePreset(cam.getVideoSize(), cam.getFps(), dai.VideoEncoderProperties.Profile.H265_MAIN) # Create MJPEG encoding for still images - stillEncoder = pipeline.createVideoEncoder() + stillEncoder = pipeline.create(dai.node.VideoEncoder) stillEncoder.setDefaultProfilePreset(cam.getStillSize(), 1, dai.VideoEncoderProperties.Profile.MJPEG) cam.still.link(stillEncoder.input) @@ -68,7 +68,7 @@ Usage videoEncoder->setDefaultProfilePreset(cam->getVideoSize(), cam->getFps(), dai::VideoEncoderProperties::Profile::H265_MAIN); // Create MJPEG encoding for still images - stillEncoder = pipeline.createVideoEncoder(); + stillEncoder = pipeline.create(dai.node.VideoEncoder); stillEncoder->setDefaultProfilePreset(cam->getStillSize(), 1, dai::VideoEncoderProperties::Profile::MJPEG); cam->still.link(stillEncoder->input); @@ -89,7 +89,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.VideoEncoder + .. autoclass:: depthai.node.VideoEncoder :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/xlink_in.rst b/docs/source/components/nodes/xlink_in.rst index a38b7325d..58dcc8b07 100644 --- a/docs/source/components/nodes/xlink_in.rst +++ b/docs/source/components/nodes/xlink_in.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - xlinkIn = pipeline.createXLinkIn() + xlinkIn = pipeline.create(dai.node.XLinkIn) .. code-tab:: c++ @@ -44,7 +44,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - xIn = pipeline.createXLinkIn() + xIn = pipeline.create(dai.node.XLinkIn) xIn.setStreamName("camControl") # Create ColorCamera beforehand @@ -95,7 +95,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.XLinkIn + .. autoclass:: depthai.node.XLinkIn :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/xlink_out.rst b/docs/source/components/nodes/xlink_out.rst index 1f09dbfec..ebf67efc2 100644 --- a/docs/source/components/nodes/xlink_out.rst +++ b/docs/source/components/nodes/xlink_out.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - xlinkOut = pipeline.createXLinkOut() + xlinkOut = pipeline.create(dai.node.XLinkOut) .. code-tab:: c++ @@ -44,7 +44,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - xOut = pipeline.createXLinkOut() + xOut = pipeline.create(dai.node.XLinkOut) xOut.setStreamName("camOut") # Here we will send camera preview (ImgFrame) to the host via XLink. @@ -76,7 +76,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.XLinkOut + .. autoclass:: depthai.node.XLinkOut :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/yolo_detection_network.rst b/docs/source/components/nodes/yolo_detection_network.rst index 73fdeb818..d4a54491f 100644 --- a/docs/source/components/nodes/yolo_detection_network.rst +++ b/docs/source/components/nodes/yolo_detection_network.rst @@ -13,7 +13,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - yoloDet = pipeline.createYoloDetectionNetwork() + yoloDet = pipeline.create(dai.node.YoloDetectionNetwork) .. code-tab:: c++ @@ -50,7 +50,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - yoloDet = pipeline.createYoloDetectionNetwork() + yoloDet = pipeline.create(dai.node.YoloDetectionNetwork) yoloDet.setBlobPath(nnBlobPath) # Yolo specific parameters @@ -88,7 +88,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.YoloDetectionNetwork + .. autoclass:: depthai.node.YoloDetectionNetwork :members: :inherited-members: :noindex: diff --git a/docs/source/components/nodes/yolo_spatial_detection_network.rst b/docs/source/components/nodes/yolo_spatial_detection_network.rst index e77eb5c76..1f3df062c 100644 --- a/docs/source/components/nodes/yolo_spatial_detection_network.rst +++ b/docs/source/components/nodes/yolo_spatial_detection_network.rst @@ -11,7 +11,7 @@ How to place it .. code-tab:: py pipeline = dai.Pipeline() - yoloSpatial = pipeline.createYoloSpatialDetectionNetwork() + yoloSpatial = pipeline.create(dai.node.YoloSpatialDetectionNetwork) .. code-tab:: c++ @@ -52,7 +52,7 @@ Usage .. code-tab:: py pipeline = dai.Pipeline() - yoloSpatial = pipeline.createYoloSpatialDetectionNetwork() + yoloSpatial = pipeline.create(dai.node.YoloSpatialDetectionNetwork) yoloSpatial.setBlobPath(nnBlobPath) # Spatial detection specific parameters @@ -101,7 +101,7 @@ Reference .. tab:: Python - .. autoclass:: depthai.YoloSpatialDetectionNetwork + .. autoclass:: depthai.node.YoloSpatialDetectionNetwork :members: :inherited-members: :noindex: diff --git a/docs/source/prerelease/script.txt b/docs/source/prerelease/script.txt deleted file mode 100644 index b375b7370..000000000 --- a/docs/source/prerelease/script.txt +++ /dev/null @@ -1,56 +0,0 @@ -Script -====== - -Scripting node enables users to write scripts that will run on the device. - -How to place it -############### - -.. tabs:: - - .. code-tab:: py - - pipeline = dai.Pipeline() - script = pipeline.create(dai.node.Script) - - .. code-tab:: c++ - - dai::Pipeline pipeline; - auto script = pipeline.create(); - -Demo -#### - -.. code-block: python - - feed_manip_config_script = pipeline.create(dai.node.Script) - feed_manip_config_script.setScriptData(""" - score, bb_cx, bb_cy, bb_w, rect_cx, rect_cy, rect_w, rotation = node.io['in'].get().getLayerFp16("result") - rr = RotatedRect() - rr.center.x = rect_cx - rr.center.y = rect_cy - rr.size.width = rect_w - rr.size.height = rect_w - rr.angle = rotation - cfg = ImageManipConfig() - cfg.setCropRotatedRect(rr, True) - cfg.setResize(224, 224) - node.io['out'].send(cfg) - """) - pp_nn.out.link(feed_manip_config_script.inputs['in']) - feed_manip_config_script.outputs['out'].link(pre_lm_manip.inputConfig) - -.. code-block: python - - script = pipeline.create(dai.node.Script) - script.setScriptData(""" - # Logging to the host can be enable with - # node.trace, node.debug, node.warn, node.error, node.critical - node.trace("Hello World") - """) - - # After initializing the device, enable log levels - device.setLogLevel(dai.LogLevel.WARN) - device.setLogOutputLevel(dai.LogLevel.WARN) - -.. include:: ../../includes/footer-short.rst diff --git a/docs/source/references/python.rst b/docs/source/references/python.rst index f7e341fe4..d177bd1ad 100644 --- a/docs/source/references/python.rst +++ b/docs/source/references/python.rst @@ -8,3 +8,14 @@ Python API Reference :special-members: __init__ :show-inheritance: :undoc-members: + +======== +Nodes +======== + +.. automodule:: depthai.node + :autosummary: + :members: + :special-members: __init__ + :show-inheritance: + :undoc-members: diff --git a/docs/source/samples/bootloader_version.rst b/docs/source/samples/bootloader_version.rst new file mode 100644 index 000000000..a568f0b50 --- /dev/null +++ b/docs/source/samples/bootloader_version.rst @@ -0,0 +1,43 @@ +Bootloader Version +================== + +This example shows basic bootloader interaction, retrieving the version of bootloader running on the device. + +Demo +#### + +Example script output + +.. code-block:: bash + + ~/depthai-python/examples$ python3 bootloader_version.py + Found device with name: 14442C1031425FD700-ma2480 + Version: 0.0.12 + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + +Source code +########### + +.. tabs:: + + .. tab:: Python + + Also `available on GitHub `__ + + .. literalinclude:: ../../../examples/bootloader_version.py + :language: python + :linenos: + + .. tab:: C++ + + Also `available on GitHub `__ + + .. literalinclude:: ../../../depthai-core/examples/src/bootloader_version.cpp + :language: cpp + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/samples/script_camera_control.rst b/docs/source/samples/script_camera_control.rst new file mode 100644 index 000000000..aec697376 --- /dev/null +++ b/docs/source/samples/script_camera_control.rst @@ -0,0 +1,42 @@ +Script camera control +===================== + +This example shows how to use :ref:`Script` node. It controls the :ref:`ColorCamera` to +capture a still image every second. + +Demo +#### + +.. raw:: html + +
+ +
+ +Setup +##### + +.. include:: /includes/install_from_pypi.rst + +Source code +########### + +.. tabs:: + + .. tab:: Python + + Also `available on GitHub `__ + + .. literalinclude:: ../../../examples/script_camera_control.py + :language: python + :linenos: + + .. tab:: C++ + + Also `available on GitHub `__ + + .. literalinclude:: ../../../depthai-core/examples/src/script_camera_control.cpp + :language: cpp + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/tutorials/code_samples.rst b/docs/source/tutorials/code_samples.rst index 8cb2bcd17..1488c7693 100644 --- a/docs/source/tutorials/code_samples.rst +++ b/docs/source/tutorials/code_samples.rst @@ -30,6 +30,8 @@ Code samples are used for automated testing. They are also a great starting poin - :ref:`IMU Accelerometer & Gyroscope` - Accelerometer and gyroscope at 500hz rate - :ref:`IMU Rotation Vector` - Rotation vector at 400 hz rate - :ref:`Edge detector` - Edge detection on input frame +- :ref:`Script camera control` - Controlling the camera with the Script node +- :ref:`Bootloader version` - Retrieves Version of Bootloader on the device .. rubric:: Complex diff --git a/docs/source/tutorials/hello_world.rst b/docs/source/tutorials/hello_world.rst index ca3a92b72..2ca159008 100644 --- a/docs/source/tutorials/hello_world.rst +++ b/docs/source/tutorials/hello_world.rst @@ -108,7 +108,7 @@ Now, first node we will add is a :class:`ColorCamera`. We will use the :code:`pr .. code-block:: python - cam_rgb = pipeline.createColorCamera() + cam_rgb = pipeline.create(dai.node.ColorCamera) cam_rgb.setPreviewSize(300, 300) cam_rgb.setInterleaved(False) @@ -119,8 +119,8 @@ to filter out the incorrect results .. code-block:: python - detection_nn = pipeline.createMobileNetDetectionNetwork() - detection_nn.setBlobPath(str(blobconverter.from_zoo(name='mobilenet-ssd', shaves=6))) + detection_nn = pipeline.create(dai.node.NeuralNetwork) + detection_nn.setBlobPath("/path/to/mobilenet-ssd.blob") detection_nn.setConfidenceThreshold(0.5) And now, let's connect a color camera :code:`preview` output to neural network input @@ -135,11 +135,11 @@ and in our case, since we want to receive data from device to host, we will use .. code-block:: python - xout_rgb = pipeline.createXLinkOut() + xout_rgb = pipeline.create(dai.node.XLinkOut) xout_rgb.setStreamName("rgb") cam_rgb.preview.link(xout_rgb.input) - xout_nn = pipeline.createXLinkOut() + xout_nn = pipeline.create(dai.node.XLinkOut) xout_nn.setStreamName("nn") detection_nn.out.link(xout_nn.input) @@ -259,7 +259,7 @@ Finally, we add a way to terminate our program (as it's running inside an infini method, that waits for a key to be pressed by user - in our case, we want to break out of the loop when user presses :code:`q` key .. code-block:: python - + if cv2.waitKey(1) == ord('q'): break @@ -271,7 +271,7 @@ Putting it all together, only thing left to do is to run the file we've prepared .. code-block:: bash python3 hello_world.py - + You're on your way! You can find the `complete code for this tutorial on GitHub `__. .. include:: /includes/footer-short.rst diff --git a/docs/source/tutorials/simple_samples.rst b/docs/source/tutorials/simple_samples.rst index 80c87b185..9e86efb33 100644 --- a/docs/source/tutorials/simple_samples.rst +++ b/docs/source/tutorials/simple_samples.rst @@ -22,6 +22,8 @@ Simple ../samples/imu_accelerometer_gyroscope.rst ../samples/imu_rotation_vector.rst ../samples/edge_detector.rst + ../samples/script_camera_control.rst + ../samples/bootloader_version.rst These samples are great starting point for the gen2 API. @@ -39,3 +41,4 @@ These samples are great starting point for the gen2 API. - :ref:`Mono & MobilenetSSD` - Runs MobileNetSSD on mono frames and displays detections on the frame - :ref:`Video & MobilenetSSD` - Runs MobileNetSSD on the video from the host - :ref:`Edge detector` - Edge detection on input frame +- :ref:`Bootloader Version` - Retrieves Version of Bootloader on the device diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 86f9e7659..dd2ec34a6 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -53,7 +53,7 @@ function(add_python_example example_name python_script_path) "PYTHONPATH=$${SYS_PATH_SEPARATOR}$ENV{PYTHONPATH}" # ASAN in case of sanitizers ${ASAN_ENVIRONMENT_VARS} - ${CMAKE_COMMAND} -DTIMEOUT_SECONDS=5 -P ${CMAKE_CURRENT_LIST_DIR}/cmake/ExecuteTestTimeout.cmake + ${CMAKE_COMMAND} -DTIMEOUT_SECONDS=10 -P ${CMAKE_CURRENT_LIST_DIR}/cmake/ExecuteTestTimeout.cmake # Actual script to run ${PYTHON_EXECUTABLE} -Werror "${CMAKE_CURRENT_LIST_DIR}/${python_script_path}" ${arguments} ) @@ -126,3 +126,4 @@ add_python_example(imu_gyroscope_accelerometer imu_gyroscope_accelerometer.py) add_python_example(imu_rotation_vector imu_rotation_vector.py) add_python_example(rgb_depth_aligned rgb_depth_aligned.py) add_python_example(edge_detector edge_detector.py) +add_python_example(script_camera_control script_camera_control.py) diff --git a/examples/script_camera_control.py b/examples/script_camera_control.py new file mode 100644 index 000000000..f0044bb90 --- /dev/null +++ b/examples/script_camera_control.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python3 +import cv2 +import depthai as dai + +# Start defining a pipeline +pipeline = dai.Pipeline() + +# Define a source - color camera +cam = pipeline.create(dai.node.ColorCamera) + +# Script node +script = pipeline.create(dai.node.Script) +script.setScript(""" + import time + ctrl = CameraControl() + ctrl.setCaptureStill(True) + while True: + time.sleep(1) + node.io['out'].send(ctrl) +""") + +# XLinkOut +xout = pipeline.create(dai.node.XLinkOut) +xout.setStreamName('still') + +# Connections +script.outputs['out'].link(cam.inputControl) +cam.still.link(xout.input) + +# Connect to device with pipeline +with dai.Device(pipeline) as device: + while True: + img = device.getOutputQueue("still").get() + cv2.imshow('still', img.getCvFrame()) + if cv2.waitKey(1) == ord('q'): + break diff --git a/src/CalibrationHandlerBindings.cpp b/src/CalibrationHandlerBindings.cpp index 0b0a4a578..b634aeccb 100644 --- a/src/CalibrationHandlerBindings.cpp +++ b/src/CalibrationHandlerBindings.cpp @@ -3,12 +3,27 @@ #include "depthai-shared/common/Point2f.hpp" #include -void CalibrationHandlerBindings::bind(pybind11::module& m){ +void CalibrationHandlerBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; - // bind pipeline - py::class_(m, "CalibrationHandler", DOC(dai, CalibrationHandler)) + // Type definitions + py::class_ calibrationHandler(m, "CalibrationHandler", DOC(dai, CalibrationHandler)); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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); + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Bindings + calibrationHandler .def(py::init<>(), DOC(dai, CalibrationHandler, CalibrationHandler)) .def(py::init(), DOC(dai, CalibrationHandler, CalibrationHandler, 2)) .def(py::init(), DOC(dai, CalibrationHandler, CalibrationHandler, 3)) diff --git a/src/CalibrationHandlerBindings.hpp b/src/CalibrationHandlerBindings.hpp index 525dd391e..8a4fdc283 100644 --- a/src/CalibrationHandlerBindings.hpp +++ b/src/CalibrationHandlerBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct CalibrationHandlerBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/DataQueueBindings.cpp b/src/DataQueueBindings.cpp index 528cd494e..557ae573f 100644 --- a/src/DataQueueBindings.cpp +++ b/src/DataQueueBindings.cpp @@ -6,11 +6,30 @@ // depthai #include "depthai/device/DataQueue.hpp" -void DataQueueBindings::bind(pybind11::module& m){ - +void DataQueueBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; using namespace std::chrono; + + // Type definitions + py::class_> dataOutputQueue(m, "DataOutputQueue", DOC(dai, DataOutputQueue)); + py::class_> dataInputQueue(m, "DataInputQueue", DOC(dai, DataInputQueue)); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // To prevent blocking whole python interpreter, blocking functions like 'get' and 'send' // are pooled with a reasonable delay and check for python interrupt signal in between. @@ -29,7 +48,7 @@ void DataQueueBindings::bind(pybind11::module& m){ throw py::value_error("Callback must take either zero, one or two arguments"); } }; - py::class_>(m, "DataOutputQueue", DOC(dai, DataOutputQueue)) + 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)) @@ -93,7 +112,7 @@ void DataQueueBindings::bind(pybind11::module& m){ ; // Bind DataInputQueue - py::class_>(m, "DataInputQueue", DOC(dai, DataInputQueue)) + dataInputQueue .def("isClosed", &DataInputQueue::isClosed, DOC(dai, DataInputQueue, isClosed)) .def("close", &DataInputQueue::close, DOC(dai, DataInputQueue, close)) .def("getName", &DataInputQueue::getName, DOC(dai, DataInputQueue, getName)) diff --git a/src/DataQueueBindings.hpp b/src/DataQueueBindings.hpp index e1f1ad7e5..9b1586944 100644 --- a/src/DataQueueBindings.hpp +++ b/src/DataQueueBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct DataQueueBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index a0ac63aa8..894ff8f9a 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -44,13 +44,86 @@ // #include "spdlog/spdlog.h" -void DatatypeBindings::bind(pybind11::module& m){ +void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; - // Bind Raw datatypes - py::class_>(m, "RawBuffer", DOC(dai, RawBuffer)) + py::class_> rawBuffer(m, "RawBuffer", DOC(dai, RawBuffer)); + py::class_> rawImgFrame(m, "RawImgFrame", DOC(dai, RawImgFrame)); + py::enum_ rawImgFrameType(rawImgFrame, "Type"); + py::class_ rawImgFrameSpecs(rawImgFrame, "Specs", DOC(dai, RawImgFrame, Specs)); + py::class_> rawNnData(m, "RawNNData", DOC(dai, RawNNData)); + py::class_ tensorInfo(m, "TensorInfo", DOC(dai, TensorInfo)); + py::enum_tensorInfoDataType(tensorInfo, "DataType"); + py::enum_tensorInfoStorageOrder(tensorInfo, "StorageOrder"); + py::class_ imgDetection(m, "ImgDetection", DOC(dai, ImgDetection)); + py::class_ spatialImgDetection(m, "SpatialImgDetection", DOC(dai, SpatialImgDetection)); + py::class_> rawImgDetections(m, "RawImgDetections", DOC(dai, RawImgDetections)); + py::class_> rawSpatialImgDetections(m, "RawSpatialImgDetections", DOC(dai, RawSpatialImgDetections)); + py::class_> rawImageManipConfig(m, "RawImageManipConfig", DOC(dai, RawImageManipConfig)); + py::class_ rawImageManipConfigCropRect(rawImageManipConfig, "CropRect", DOC(dai, RawImageManipConfig, CropRect)); + py::class_ rawImageManipCropConfig(rawImageManipConfig, "CropConfig", DOC(dai, RawImageManipConfig, CropConfig)); + py::class_rawImageManipConfigResizeConfig(rawImageManipConfig, "ResizeConfig", DOC(dai, RawImageManipConfig, ResizeConfig)); + py::class_ rawImageManipConfigFormatConfig(rawImageManipConfig, "FormatConfig", DOC(dai, RawImageManipConfig, FormatConfig)); + py::class_> rawCameraControl(m, "RawCameraControl", DOC(dai, RawCameraControl)); + py::class_ tracklet(m, "Tracklet", DOC(dai, Tracklet)); + py::enum_ trackletTrackingStatus(tracklet, "TrackingStatus", DOC(dai, Tracklet, TrackingStatus)); + py::class_> rawTacklets(m, "RawTracklets", DOC(dai, RawTracklets)); + py::class_> imuReport(m, "IMUReport", DOC(dai, IMUReport)); + py::enum_ imuReportAccuracy(imuReport, "Accuracy"); + py::class_> imuReportAccelerometer(m, "IMUReportAccelerometer", DOC(dai, IMUReportAccelerometer)); + py::class_> imuReportGyroscope(m, "IMUReportGyroscope", DOC(dai, IMUReportGyroscope)); + py::class_> imuReportMagneticField(m, "IMUReportMagneticField", DOC(dai, IMUReportMagneticField)); + py::class_> imuReportRotationVectorWAcc(m, "IMUReportRotationVectorWAcc", DOC(dai, IMUReportRotationVectorWAcc)); + py::class_ imuPacket(m, "IMUPacket", DOC(dai, IMUPacket)); + py::class_> rawIMUPackets(m, "RawIMUData", DOC(dai, RawIMUData)); + 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_ rawCameraControlAntiBandingMode(rawCameraControl, "AntiBandingMode", DOC(dai, RawCameraControl, AntiBandingMode)); + py::enum_ rawCameraControlEffectMode(rawCameraControl, "EffectMode", DOC(dai, RawCameraControl, EffectMode)); + py::class_> rawSystemInformation(m, "RawSystemInformation", DOC(dai, RawSystemInformation)); + py::class_> adatatype(m, "ADatatype", DOC(dai, ADatatype)); + py::class_> buffer(m, "Buffer", DOC(dai, Buffer)); + py::class_> imgFrame(m, "ImgFrame", DOC(dai, ImgFrame)); + py::class_ rotatedRect(m, "RotatedRect", DOC(dai, RotatedRect)); + py::class_> nnData(m, "NNData", DOC(dai, NNData)); + py::class_> imgDetections(m, "ImgDetections", DOC(dai, ImgDetections)); + py::class_> spatialImgDetections(m, "SpatialImgDetections", DOC(dai, SpatialImgDetections)); + py::class_> imageManipConfig(m, "ImageManipConfig", DOC(dai, ImageManipConfig)); + py::class_> cameraControl(m, "CameraControl", DOC(dai, CameraControl)); + py::class_> systemInformation(m, "SystemInformation", DOC(dai, SystemInformation)); + py::class_ spatialLocations(m, "SpatialLocations", DOC(dai, SpatialLocations)); + py::class_ rect(m, "Rect", DOC(dai, Rect)); + py::class_ spatialLocationCalculatorConfigThresholds(m, "SpatialLocationCalculatorConfigThresholds", DOC(dai, SpatialLocationCalculatorConfigThresholds)); + py::class_ spatialLocationCalculatorConfigData(m, "SpatialLocationCalculatorConfigData", DOC(dai, SpatialLocationCalculatorConfigData)); + py::class_> spatialLocationCalculatorData(m, "SpatialLocationCalculatorData", DOC(dai, SpatialLocationCalculatorData)); + py::class_> spatialLocationCalculatorConfig(m, "SpatialLocationCalculatorConfig", DOC(dai, SpatialLocationCalculatorConfig)); + py::class_> tracklets(m, "Tracklets", DOC(dai, Tracklets)); + py::class_> imuData(m, "IMUData", DOC(dai, IMUData)); + py::class_> rawStereoDepthConfig(m, "RawStereoDepthConfig", DOC(dai, RawStereoDepthConfig)); + py::class_> stereoDepthConfig(m, "StereoDepthConfig", DOC(dai, StereoDepthConfig)); + py::class_ edgeDetectorConfigData(m, "EdgeDetectorConfigData", DOC(dai, EdgeDetectorConfigData)); + py::class_> rawEdgeDetectorConfig(m, "RawEdgeDetectorConfig", DOC(dai, RawEdgeDetectorConfig)); + py::class_> edgeDetectorConfig(m, "EdgeDetectorConfig", DOC(dai, EdgeDetectorConfig)); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + + rawBuffer .def(py::init<>()) .def_property("data", [](py::object &obj){ dai::RawBuffer &a = obj.cast(); @@ -62,8 +135,7 @@ void DatatypeBindings::bind(pybind11::module& m){ ; - // Bind RawImgFrame - py::class_> rawImgFrame(m, "RawImgFrame", DOC(dai, RawImgFrame)); + rawImgFrame .def(py::init<>()) .def_readwrite("fb", &RawImgFrame::fb) @@ -92,7 +164,8 @@ void DatatypeBindings::bind(pybind11::module& m){ ) ; - py::enum_(rawImgFrame, "Type") + + rawImgFrameType .value("YUV422i", RawImgFrame::Type::YUV422i) .value("YUV444p", RawImgFrame::Type::YUV444p) .value("YUV420p", RawImgFrame::Type::YUV420p) @@ -128,7 +201,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .value("NONE", RawImgFrame::Type::NONE) ; - py::class_(rawImgFrame, "Specs", DOC(dai, RawImgFrame, Specs)) + rawImgFrameSpecs .def(py::init<>()) .def_readwrite("type", &RawImgFrame::Specs::type) .def_readwrite("width", &RawImgFrame::Specs::width) @@ -141,15 +214,12 @@ void DatatypeBindings::bind(pybind11::module& m){ ; - // NNData - py::class_> rawNnData(m, "RawNNData", DOC(dai, RawNNData)); rawNnData .def(py::init<>()) .def_readwrite("tensors", &RawNNData::tensors) .def_readwrite("batchSize", &RawNNData::batchSize) ; - py::class_ tensorInfo(m, "TensorInfo", DOC(dai, TensorInfo)); tensorInfo .def(py::init<>()) .def_readwrite("order", &TensorInfo::order) @@ -161,7 +231,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("offset", &TensorInfo::offset) ; - py::enum_(tensorInfo, "DataType") + tensorInfoDataType .value("FP16", TensorInfo::DataType::FP16) .value("U8F", TensorInfo::DataType::U8F) .value("INT", TensorInfo::DataType::INT) @@ -169,7 +239,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .value("I8", TensorInfo::DataType::I8) ; - py::enum_(tensorInfo, "StorageOrder") + tensorInfoStorageOrder .value("NHWC", TensorInfo::StorageOrder::NHWC) .value("NHCW", TensorInfo::StorageOrder::NHCW) .value("NCHW", TensorInfo::StorageOrder::NCHW) @@ -186,7 +256,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .value("W", TensorInfo::StorageOrder::W) ; - py::class_(m, "ImgDetection", DOC(dai, ImgDetection)) + imgDetection .def(py::init<>()) .def_readwrite("label", &ImgDetection::label) .def_readwrite("confidence", &ImgDetection::confidence) @@ -196,25 +266,23 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("ymax", &ImgDetection::ymax) ; - py::class_(m, "SpatialImgDetection", DOC(dai, SpatialImgDetection)) + + spatialImgDetection .def(py::init<>()) .def_readwrite("spatialCoordinates", &SpatialImgDetection::spatialCoordinates) ; - py::class_> RawImgDetections(m, "RawImgDetections", DOC(dai, RawImgDetections)); - RawImgDetections + rawImgDetections .def(py::init<>()) .def_readwrite("detections", &RawImgDetections::detections) ; - py::class_> RawSpatialImgDetections(m, "RawSpatialImgDetections", DOC(dai, RawSpatialImgDetections)); - RawSpatialImgDetections + rawSpatialImgDetections .def(py::init<>()) .def_readwrite("detections", &RawSpatialImgDetections::detections) ; // Bind RawImageManipConfig - py::class_> rawImageManipConfig(m, "RawImageManipConfig", DOC(dai, RawImageManipConfig)); rawImageManipConfig .def(py::init<>()) .def_readwrite("enableFormat", &RawImageManipConfig::enableFormat) @@ -225,7 +293,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("formatConfig", &RawImageManipConfig::formatConfig) ; - py::class_(rawImageManipConfig, "CropRect", DOC(dai, RawImageManipConfig, CropRect)) + rawImageManipConfigCropRect .def(py::init<>()) .def_readwrite("xmin", &RawImageManipConfig::CropRect::xmin) .def_readwrite("ymin", &RawImageManipConfig::CropRect::ymin) @@ -233,7 +301,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("ymax", &RawImageManipConfig::CropRect::ymax) ; - py::class_(rawImageManipConfig, "CropConfig", DOC(dai, RawImageManipConfig, CropConfig)) + rawImageManipCropConfig .def(py::init<>()) .def_readwrite("cropRect", &RawImageManipConfig::CropConfig::cropRect) .def_readwrite("cropRotatedRect", &RawImageManipConfig::CropConfig::cropRotatedRect) @@ -244,7 +312,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("normalizedCoords", &RawImageManipConfig::CropConfig::normalizedCoords) ; - py::class_(rawImageManipConfig, "ResizeConfig", DOC(dai, RawImageManipConfig, ResizeConfig)) + rawImageManipConfigResizeConfig .def(py::init<>()) .def_readwrite("width", &RawImageManipConfig::ResizeConfig::width) .def_readwrite("height", &RawImageManipConfig::ResizeConfig::height) @@ -263,7 +331,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("keepAspectRatio", &RawImageManipConfig::ResizeConfig::keepAspectRatio) ; - py::class_(rawImageManipConfig, "FormatConfig", DOC(dai, RawImageManipConfig, FormatConfig)) + rawImageManipConfigFormatConfig .def(py::init<>()) .def_readwrite("type", &RawImageManipConfig::FormatConfig::type) .def_readwrite("flipHorizontal", &RawImageManipConfig::FormatConfig::flipHorizontal) @@ -271,7 +339,6 @@ void DatatypeBindings::bind(pybind11::module& m){ // Bind RawCameraControl - py::class_> rawCameraControl(m, "RawCameraControl", DOC(dai, RawCameraControl)); rawCameraControl .def(py::init<>()) .def_readwrite("cmdMask", &RawCameraControl::cmdMask) @@ -280,7 +347,6 @@ void DatatypeBindings::bind(pybind11::module& m){ // TODO add more raw types here, not directly used ; - py::class_ tracklet(m, "Tracklet", DOC(dai, Tracklet)); tracklet .def(py::init<>()) .def_readwrite("roi", &Tracklet::roi) @@ -291,7 +357,7 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("spatialCoordinates", &Tracklet::spatialCoordinates) ; - py::enum_(tracklet, "TrackingStatus", DOC(dai, Tracklet, TrackingStatus)) + trackletTrackingStatus .value("NEW", Tracklet::TrackingStatus::NEW) .value("TRACKED", Tracklet::TrackingStatus::TRACKED) .value("LOST", Tracklet::TrackingStatus::LOST) @@ -299,50 +365,49 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Bind RawTracklets - py::class_> rawTacklets(m, "RawTracklets", DOC(dai, RawTracklets)); rawTacklets .def(py::init<>()) .def_readwrite("tracklets", &RawTracklets::tracklets) ; - py::class_> imureport(m, "IMUReport", DOC(dai, IMUReport)); - imureport + imuReport .def(py::init<>()) .def_readwrite("sequence", &IMUReport::sequence) .def_readwrite("accuracy", &IMUReport::accuracy) .def_readwrite("timestamp", &IMUReport::timestamp) ; - py::enum_(imureport, "Accuracy") + + imuReportAccuracy .value("UNRELIABLE", IMUReport::Accuracy::UNRELIABLE) .value("LOW", IMUReport::Accuracy::LOW) .value("MEDIUM", IMUReport::Accuracy::MEDIUM) .value("HIGH", IMUReport::Accuracy::HIGH) ; - py::class_>(m, "IMUReportAccelerometer", DOC(dai, IMUReportAccelerometer)) + imuReportAccelerometer .def(py::init<>()) .def_readwrite("x", &IMUReportAccelerometer::x) .def_readwrite("y", &IMUReportAccelerometer::y) .def_readwrite("z", &IMUReportAccelerometer::z) ; - py::class_>(m, "IMUReportGyroscope", DOC(dai, IMUReportGyroscope)) + imuReportGyroscope .def(py::init<>()) .def_readwrite("x", &IMUReportGyroscope::x) .def_readwrite("y", &IMUReportGyroscope::y) .def_readwrite("z", &IMUReportGyroscope::z) ; - py::class_>(m, "IMUReportMagneticField", DOC(dai, IMUReportMagneticField)) + imuReportMagneticField .def(py::init<>()) .def_readwrite("x", &IMUReportMagneticField::x) .def_readwrite("y", &IMUReportMagneticField::y) .def_readwrite("z", &IMUReportMagneticField::z) ; - py::class_>(m, "IMUReportRotationVectorWAcc", DOC(dai, IMUReportRotationVectorWAcc)) + imuReportRotationVectorWAcc .def(py::init<>()) .def_readwrite("i", &IMUReportRotationVectorWAcc::i) .def_readwrite("j", &IMUReportRotationVectorWAcc::j) @@ -393,8 +458,7 @@ void DatatypeBindings::bind(pybind11::module& m){ #endif - py::class_ imuPackets(m, "IMUPacket", DOC(dai, IMUPacket)); - imuPackets + imuPacket .def(py::init<>()) .def_readwrite("acceleroMeter", &IMUPacket::acceleroMeter) .def_readwrite("gyroscope", &IMUPacket::gyroscope) @@ -418,7 +482,6 @@ void DatatypeBindings::bind(pybind11::module& m){ // Bind RawIMUData - py::class_> rawIMUPackets(m, "RawIMUData", DOC(dai, RawIMUData)); rawIMUPackets .def(py::init<>()) .def_readwrite("packets", &RawIMUData::packets) @@ -428,7 +491,7 @@ void DatatypeBindings::bind(pybind11::module& m){ // The enum fields will also be exposed in 'CameraControl', store them for later std::vector camCtrlAttr; camCtrlAttr.push_back("AutoFocusMode"); - py::enum_(rawCameraControl, "AutoFocusMode", DOC(dai, RawCameraControl, AutoFocusMode)) + rawCameraControlAutoFocusMode .value("OFF", RawCameraControl::AutoFocusMode::OFF) .value("AUTO", RawCameraControl::AutoFocusMode::AUTO) .value("MACRO", RawCameraControl::AutoFocusMode::MACRO) @@ -438,7 +501,7 @@ void DatatypeBindings::bind(pybind11::module& m){ ; camCtrlAttr.push_back("AutoWhiteBalanceMode"); - py::enum_(rawCameraControl, "AutoWhiteBalanceMode", DOC(dai, RawCameraControl, AutoWhiteBalanceMode)) + rawCameraControlAutoWhiteBalanceMode .value("OFF", RawCameraControl::AutoWhiteBalanceMode::OFF) .value("AUTO", RawCameraControl::AutoWhiteBalanceMode::AUTO) .value("INCANDESCENT", RawCameraControl::AutoWhiteBalanceMode::INCANDESCENT) @@ -451,7 +514,7 @@ void DatatypeBindings::bind(pybind11::module& m){ ; camCtrlAttr.push_back("SceneMode"); - py::enum_(rawCameraControl, "SceneMode", DOC(dai, RawCameraControl, SceneMode)) + rawCameraControlSceneMode .value("UNSUPPORTED", RawCameraControl::SceneMode::UNSUPPORTED) .value("FACE_PRIORITY", RawCameraControl::SceneMode::FACE_PRIORITY) .value("ACTION", RawCameraControl::SceneMode::ACTION) @@ -472,7 +535,7 @@ void DatatypeBindings::bind(pybind11::module& m){ ; camCtrlAttr.push_back("AntiBandingMode"); - py::enum_(rawCameraControl, "AntiBandingMode", DOC(dai, RawCameraControl, AntiBandingMode)) + rawCameraControlAntiBandingMode .value("OFF", RawCameraControl::AntiBandingMode::OFF) .value("MAINS_50_HZ", RawCameraControl::AntiBandingMode::MAINS_50_HZ) .value("MAINS_60_HZ", RawCameraControl::AntiBandingMode::MAINS_60_HZ) @@ -480,7 +543,7 @@ void DatatypeBindings::bind(pybind11::module& m){ ; camCtrlAttr.push_back("EffectMode"); - py::enum_(rawCameraControl, "EffectMode", DOC(dai, RawCameraControl, EffectMode)) + rawCameraControlEffectMode .value("OFF", RawCameraControl::EffectMode::OFF) .value("MONO", RawCameraControl::EffectMode::MONO) .value("NEGATIVE", RawCameraControl::EffectMode::NEGATIVE) @@ -493,7 +556,6 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Bind RawSystemInformation - py::class_> rawSystemInformation(m, "RawSystemInformation", DOC(dai, RawSystemInformation)); rawSystemInformation .def(py::init<>()) .def_readwrite("ddrMemoryUsage", &RawSystemInformation::ddrMemoryUsage) @@ -507,10 +569,11 @@ void DatatypeBindings::bind(pybind11::module& m){ // Bind non-raw 'helper' datatypes - py::class_>(m, "ADatatype", DOC(dai, ADatatype)) + adatatype .def("getRaw", &ADatatype::getRaw); - py::class_>(m, "Buffer", DOC(dai, Buffer)) + + buffer .def(py::init<>(), DOC(dai, Buffer, Buffer)) // obj is "Python" object, which we used then to bind the numpy arrays lifespan to @@ -527,7 +590,7 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Bind ImgFrame - py::class_>(m, "ImgFrame", DOC(dai, ImgFrame)) + imgFrame .def(py::init<>()) // getters .def("getTimestamp", &ImgFrame::getTimestamp, DOC(dai, ImgFrame, getTimestamp)) @@ -735,7 +798,7 @@ void DatatypeBindings::bind(pybind11::module& m){ m.attr("ImgFrame").attr("Type") = m.attr("RawImgFrame").attr("Type"); m.attr("ImgFrame").attr("Specs") = m.attr("RawImgFrame").attr("Specs"); - py::class_(m, "RotatedRect", DOC(dai, RotatedRect)) + rotatedRect .def(py::init<>()) .def_readwrite("center", &RotatedRect::center) .def_readwrite("size", &RotatedRect::size) @@ -743,7 +806,8 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Bind NNData - py::class_>(m, "NNData", DOC(dai, NNData)) + + nnData .def(py::init<>(), DOC(dai, NNData, NNData)) // setters .def("setLayer", [](NNData& obj, const std::string& name, py::array_t data){ @@ -767,19 +831,22 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Bind ImgDetections - py::class_>(m, "ImgDetections", DOC(dai, ImgDetections)) + + imgDetections .def(py::init<>(), DOC(dai, ImgDetections, ImgDetections)) .def_property("detections", [](ImgDetections& det) { return &det.detections; }, [](ImgDetections& det, std::vector val) { det.detections = val; }, DOC(dai, ImgDetections, detections)) ; // Bind SpatialImgDetections - py::class_>(m, "SpatialImgDetections", DOC(dai, SpatialImgDetections)) + + spatialImgDetections .def(py::init<>()) .def_property("detections", [](SpatialImgDetections& det) { return &det.detections; }, [](SpatialImgDetections& det, std::vector val) { det.detections = val; }) ; // Bind ImageManipConfig - py::class_>(m, "ImageManipConfig", DOC(dai, ImageManipConfig)) + + imageManipConfig .def(py::init<>()) // setters .def("setCropRect", &ImageManipConfig::setCropRect, py::arg("xmin"), py::arg("ymin"), py::arg("xmax"), py::arg("xmax"), DOC(dai, ImageManipConfig, setCropRect)) @@ -810,7 +877,8 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Bind CameraControl - py::class_>(m, "CameraControl", DOC(dai, CameraControl)) + + cameraControl .def(py::init<>(), DOC(dai, CameraControl, CameraControl)) // setters .def("setCaptureStill", &CameraControl::setCaptureStill, py::arg("capture"), DOC(dai, CameraControl, setCaptureStill)) @@ -845,7 +913,8 @@ void DatatypeBindings::bind(pybind11::module& m){ } // Bind SystemInformation - py::class_>(m, "SystemInformation", DOC(dai, SystemInformation)) + + systemInformation .def(py::init<>()) .def_property("ddrMemoryUsage", [](SystemInformation& i) { return &i.ddrMemoryUsage; }, [](SystemInformation& i, MemoryInfo val) { i.ddrMemoryUsage = val; } ) .def_property("cmxMemoryUsage", [](SystemInformation& i) { return &i.cmxMemoryUsage; }, [](SystemInformation& i, MemoryInfo val) { i.cmxMemoryUsage = val; } ) @@ -856,7 +925,8 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_property("chipTemperature", [](SystemInformation& i) { return &i.chipTemperature; }, [](SystemInformation& i, ChipTemperature val) { i.chipTemperature = val; } ) ; - py::class_ (m, "SpatialLocations", DOC(dai, SpatialLocations)) + + spatialLocations .def(py::init<>()) .def_readwrite("config", &SpatialLocations::config, DOC(dai, SpatialLocations, config)) .def_readwrite("depthAverage", &SpatialLocations::depthAverage, DOC(dai, SpatialLocations, depthAverage)) @@ -867,7 +937,8 @@ void DatatypeBindings::bind(pybind11::module& m){ ; - py::class_ (m, "Rect", DOC(dai, Rect)) + + rect .def(py::init<>()) .def(py::init()) .def(py::init()) @@ -888,26 +959,30 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("height", &Rect::height) ; - py::class_ (m, "SpatialLocationCalculatorConfigThresholds", DOC(dai, SpatialLocationCalculatorConfigThresholds)) + + spatialLocationCalculatorConfigThresholds .def(py::init<>()) .def_readwrite("lowerThreshold", &SpatialLocationCalculatorConfigThresholds::lowerThreshold) .def_readwrite("upperThreshold", &SpatialLocationCalculatorConfigThresholds::upperThreshold) ; - py::class_ (m, "SpatialLocationCalculatorConfigData", DOC(dai, SpatialLocationCalculatorConfigData)) + + spatialLocationCalculatorConfigData .def(py::init<>()) .def_readwrite("roi", &SpatialLocationCalculatorConfigData::roi) .def_readwrite("depthThresholds", &SpatialLocationCalculatorConfigData::depthThresholds) ; // Bind SpatialLocationCalculatorData - py::class_>(m, "SpatialLocationCalculatorData", DOC(dai, SpatialLocationCalculatorData)) + + spatialLocationCalculatorData .def(py::init<>()) .def("getSpatialLocations", &SpatialLocationCalculatorData::getSpatialLocations, DOC(dai, SpatialLocationCalculatorData, getSpatialLocations)) ; // SpatialLocationCalculatorConfig (after ConfigData) - py::class_>(m, "SpatialLocationCalculatorConfig", DOC(dai, SpatialLocationCalculatorConfig)) + + spatialLocationCalculatorConfig .def(py::init<>()) // setters .def("setROIs", &SpatialLocationCalculatorConfig::setROIs, py::arg("ROIs"), DOC(dai, SpatialLocationCalculatorConfig, setROIs)) @@ -916,27 +991,27 @@ void DatatypeBindings::bind(pybind11::module& m){ ; // Tracklets (after ConfigData) - py::class_>(m, "Tracklets", DOC(dai, Tracklets)) + + tracklets .def(py::init<>()) .def_property("tracklets", [](Tracklets& track) { return &track.tracklets; }, [](Tracklets& track, std::vector val) { track.tracklets = val; }, DOC(dai, Tracklets, tracklets)) ; - // IMUData (after ConfigData) - py::class_>(m, "IMUData", DOC(dai, IMUData)) + + imuData .def(py::init<>()) .def_property("packets", [](IMUData& imuDta) { return &imuDta.packets; }, [](IMUData& imuDta, std::vector val) { imuDta.packets = val; }, DOC(dai, IMUData, packets)) ; - // Bind RawStereoDepthConfig - py::class_> rawStereoDepthConfig(m, "RawStereoDepthConfig", DOC(dai, RawStereoDepthConfig)); + rawStereoDepthConfig .def(py::init<>()) .def_readwrite("config", &RawStereoDepthConfig::config) ; - // StereoDepthConfig (after ConfigData) - py::class_>(m, "StereoDepthConfig", DOC(dai, StereoDepthConfig)) + + stereoDepthConfig .def(py::init<>()) .def("setConfidenceThreshold", &StereoDepthConfig::setConfidenceThreshold, py::arg("confThr"), DOC(dai, StereoDepthConfig, setConfidenceThreshold)) .def("setMedianFilter", &StereoDepthConfig::setMedianFilter, py::arg("median"), DOC(dai, StereoDepthConfig, setMedianFilter)) @@ -948,22 +1023,20 @@ void DatatypeBindings::bind(pybind11::module& m){ .def("getLeftRightCheckThreshold", &StereoDepthConfig::getLeftRightCheckThreshold, DOC(dai, StereoDepthConfig, getLeftRightCheckThreshold)) ; - - py::class_ (m, "EdgeDetectorConfigData", DOC(dai, EdgeDetectorConfigData)) + edgeDetectorConfigData .def(py::init<>()) .def_readwrite("sobelFilterHorizontalKernel", &EdgeDetectorConfigData::sobelFilterHorizontalKernel, DOC(dai, EdgeDetectorConfigData, sobelFilterHorizontalKernel)) .def_readwrite("sobelFilterVerticalKernel", &EdgeDetectorConfigData::sobelFilterVerticalKernel, DOC(dai, EdgeDetectorConfigData, sobelFilterVerticalKernel)) ; - // Bind RawEdgeDetectorConfig - py::class_> rawEdgeDetectorConfig(m, "RawEdgeDetectorConfig", DOC(dai, RawEdgeDetectorConfig)); + rawEdgeDetectorConfig .def(py::init<>()) .def_readwrite("config", &RawEdgeDetectorConfig::config) ; - // EdgeDetectorConfig (after ConfigData) - py::class_>(m, "EdgeDetectorConfig", DOC(dai, EdgeDetectorConfig)) + + edgeDetectorConfig .def(py::init<>()) .def("setSobelFilterKernels", &EdgeDetectorConfig::setSobelFilterKernels, py::arg("horizontalKernel"), py::arg("verticalKernel"), DOC(dai, EdgeDetectorConfig, setSobelFilterKernels)) .def("getConfigData", &EdgeDetectorConfig::getConfigData, DOC(dai, EdgeDetectorConfig, getConfigData)) diff --git a/src/DatatypeBindings.hpp b/src/DatatypeBindings.hpp index b7192cb20..21ff435ee 100644 --- a/src/DatatypeBindings.hpp +++ b/src/DatatypeBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct DatatypeBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index f2c8d3c72..3f242a698 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -112,17 +112,37 @@ std::vector deviceGetQueueEventsHelper(dai::Device& d, const std::v } -void DeviceBindings::bind(pybind11::module& m){ +void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; + // Type definitions + py::class_ device(m, "Device", DOC(dai, Device)); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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); + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Bind Device, using DeviceWrapper to be able to destruct the object by calling close() - py::class_(m, "Device", DOC(dai, Device)) + device // Python only methods .def("__enter__", [](py::object obj){ return obj; }) - .def("__exit__", [](Device& d, py::object type, py::object value, py::object traceback) { d.close(); }) - .def("close", &Device::close, "Closes the connection to device. Better alternative is the usage of context manager: `with depthai.Device(pipeline) as device:`") + .def("__exit__", [](Device& d, py::object type, py::object value, py::object traceback) { + py::gil_scoped_release release; + d.close(); + }) + .def("close", [](Device& d) { py::gil_scoped_release release; d.close(); }, "Closes the connection to device. Better alternative is the usage of context manager: `with depthai.Device(pipeline) as device:`") .def("isClosed", &Device::isClosed, "Check if the device is still connected`") //dai::Device methods @@ -155,7 +175,6 @@ void DeviceBindings::bind(pybind11::module& m){ return std::unique_ptr(new Device(pipeline, deviceInfo, pathToCmd)); }), py::arg("pipeline"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, Device, Device, 5)) - // Device constructor - OpenVINO version .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Device, Device, 6)) .def(py::init([](OpenVINO::Version version, bool usb2Mode){ @@ -175,16 +194,17 @@ void DeviceBindings::bind(pybind11::module& m){ return std::unique_ptr(new Device(version, deviceInfo, pathToCmd)); }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, Device, Device, 10)) - .def("isPipelineRunning", &Device::isPipelineRunning, DOC(dai, Device, isPipelineRunning)) + .def("isPipelineRunning", [](Device& d) { py::gil_scoped_release release; return d.isPipelineRunning(); }, DOC(dai, Device, isPipelineRunning)) .def("startPipeline", [](Device& d){ // Issue an deprecation warning PyErr_WarnEx(PyExc_DeprecationWarning, "Device(pipeline) starts the pipeline automatically. Use Device() and startPipeline(pipeline) otherwise", 1); HEDLEY_DIAGNOSTIC_PUSH HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + py::gil_scoped_release release; d.startPipeline(); HEDLEY_DIAGNOSTIC_POP }, DOC(dai, Device, startPipeline)) - .def("startPipeline", py::overload_cast(&Device::startPipeline), DOC(dai, Device, startPipeline, 2)) + .def("startPipeline", [](Device& d, const Pipeline& pipeline) { py::gil_scoped_release release; return d.startPipeline(pipeline); }, DOC(dai, Device, startPipeline, 2)) .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) @@ -226,25 +246,29 @@ void DeviceBindings::bind(pybind11::module& m){ }, py::arg("timeout") = std::chrono::microseconds(-1), DOC(dai, Device, getQueueEvent, 4)) //.def("setCallback", DeviceWrapper::wrap(&Device::setCallback), py::arg("name"), py::arg("callback")) - .def("setLogLevel", &Device::setLogLevel, py::arg("level"), DOC(dai, Device, setLogLevel)) - .def("getLogLevel", &Device::getLogLevel, DOC(dai, Device, getLogLevel)) - .def("getDeviceInfo", &Device::getDeviceInfo, DOC(dai, Device, getDeviceInfo)) - .def("setSystemInformationLoggingRate", &Device::setSystemInformationLoggingRate, py::arg("rateHz"), DOC(dai, Device, setSystemInformationLoggingRate)) - .def("getSystemInformationLoggingRate", &Device::getSystemInformationLoggingRate, DOC(dai, Device, getSystemInformationLoggingRate)) - .def("getMxId", &Device::getMxId, DOC(dai, Device, getMxId)) - .def("getConnectedCameras", &Device::getConnectedCameras, DOC(dai, Device, getConnectedCameras)) - .def("getDdrMemoryUsage", &Device::getDdrMemoryUsage, DOC(dai, Device, getDdrMemoryUsage)) - .def("getCmxMemoryUsage", &Device::getCmxMemoryUsage, DOC(dai, Device, getCmxMemoryUsage)) - .def("getLeonCssHeapUsage", &Device::getLeonCssHeapUsage, DOC(dai, Device, getLeonCssHeapUsage)) - .def("getLeonMssHeapUsage", &Device::getLeonMssHeapUsage, DOC(dai, Device, getLeonMssHeapUsage)) - .def("getChipTemperature", &Device::getChipTemperature, DOC(dai, Device, getChipTemperature)) - .def("getLeonCssCpuUsage", &Device::getLeonCssCpuUsage, DOC(dai, Device, getLeonCssCpuUsage)) - .def("getLeonMssCpuUsage", &Device::getLeonMssCpuUsage, DOC(dai, Device, getLeonMssCpuUsage)) - .def("getUsbSpeed", &Device::getUsbSpeed, DOC(dai, Device, getUsbSpeed)) + + // Doesn't require GIL release (eg, don't do RPC or long blocking things in background) .def("setLogOutputLevel", &Device::setLogOutputLevel, py::arg("level"), DOC(dai, Device, setLogOutputLevel)) .def("getLogOutputLevel", &Device::getLogOutputLevel, DOC(dai, Device, getLogOutputLevel)) - .def("addLogCallback", &Device::addLogCallback, py::arg("callback"), DOC(dai, Device, addLogCallback)) - .def("removeLogCallback", &Device::removeLogCallback, py::arg("callbackId"), DOC(dai, Device, removeLogCallback)) - ; + + // Requires GIL release + .def("setLogLevel", [](Device& d, LogLevel l) { py::gil_scoped_release release; d.setLogLevel(l); }, py::arg("level"), DOC(dai, Device, setLogLevel)) + .def("getLogLevel", [](Device& d) { py::gil_scoped_release release; return d.getLogLevel(); }, DOC(dai, Device, getLogLevel)) + .def("setSystemInformationLoggingRate", [](Device& d, float hz) { py::gil_scoped_release release; d.setSystemInformationLoggingRate(hz); }, py::arg("rateHz"), DOC(dai, Device, setSystemInformationLoggingRate)) + .def("getSystemInformationLoggingRate", [](Device& d) { py::gil_scoped_release release; return d.getSystemInformationLoggingRate(); }, DOC(dai, Device, getSystemInformationLoggingRate)) + .def("getConnectedCameras", [](Device& d) { py::gil_scoped_release release; return d.getConnectedCameras(); }, DOC(dai, Device, getConnectedCameras)) + .def("getDdrMemoryUsage", [](Device& d) { py::gil_scoped_release release; return d.getDdrMemoryUsage(); }, DOC(dai, Device, getDdrMemoryUsage)) + .def("getCmxMemoryUsage", [](Device& d) { py::gil_scoped_release release; return d.getCmxMemoryUsage(); }, DOC(dai, Device, getCmxMemoryUsage)) + .def("getLeonCssHeapUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonCssHeapUsage(); }, DOC(dai, Device, getLeonCssHeapUsage)) + .def("getLeonMssHeapUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonMssHeapUsage(); }, DOC(dai, Device, getLeonMssHeapUsage)) + .def("getChipTemperature", [](Device& d) { py::gil_scoped_release release; return d.getChipTemperature(); }, DOC(dai, Device, getChipTemperature)) + .def("getLeonCssCpuUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonCssCpuUsage(); }, DOC(dai, Device, getLeonCssCpuUsage)) + .def("getLeonMssCpuUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonMssCpuUsage(); }, DOC(dai, Device, getLeonMssCpuUsage)) + .def("addLogCallback", [](Device& d, std::function callback) { py::gil_scoped_release release; return d.addLogCallback(callback); }, py::arg("callback"), DOC(dai, Device, addLogCallback)) + .def("removeLogCallback", [](Device& d, int cbId) { py::gil_scoped_release release; return d.removeLogCallback(cbId); }, py::arg("callbackId"), DOC(dai, Device, removeLogCallback)) + .def("getUsbSpeed", [](Device& d) { py::gil_scoped_release release; return d.getUsbSpeed(); }, DOC(dai, Device, getUsbSpeed)) + .def("getDeviceInfo", [](Device& d) { py::gil_scoped_release release; return d.getDeviceInfo(); }, DOC(dai, Device, getDeviceInfo)) + .def("getMxId", [](Device& d) { py::gil_scoped_release release; return d.getMxId(); }, DOC(dai, Device, getMxId)); + ; } \ No newline at end of file diff --git a/src/DeviceBindings.hpp b/src/DeviceBindings.hpp index a63215e27..a962249d3 100644 --- a/src/DeviceBindings.hpp +++ b/src/DeviceBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct DeviceBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/DeviceBootloaderBindings.cpp b/src/DeviceBootloaderBindings.cpp index 888236b53..890364a30 100644 --- a/src/DeviceBootloaderBindings.cpp +++ b/src/DeviceBootloaderBindings.cpp @@ -3,14 +3,33 @@ // depthai #include "depthai/device/DeviceBootloader.hpp" -void DeviceBootloaderBindings::bind(pybind11::module& m){ +void DeviceBootloaderBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; - // Bind DeviceBootloader + // Type definitions py::class_ deviceBootloader(m, "DeviceBootloader", DOC(dai, DeviceBootloader)); + py::class_ deviceBootloaderVersion(deviceBootloader, "Version", DOC(dai, DeviceBootloader, Version)); + py::enum_ deviceBootloaderType(deviceBootloader, "Type"); + py::enum_ deviceBootloaderMemory(deviceBootloader, "Memory"); + py::enum_ deviceBootloaderSection(deviceBootloader, "Section"); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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); + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// - py::class_(deviceBootloader, "Version", DOC(dai, DeviceBootloader, Version)) + + // Bind DeviceBootloader + deviceBootloaderVersion .def(py::init(), py::arg("v"), DOC(dai, DeviceBootloader, Version, Version)) .def(py::init(), py::arg("major"), py::arg("minor"), py::arg("patch"), DOC(dai, DeviceBootloader, Version, Version, 2)) .def("__str__", &DeviceBootloader::Version::toString) @@ -19,15 +38,15 @@ void DeviceBootloaderBindings::bind(pybind11::module& m){ .def("__gt__", &DeviceBootloader::Version::operator>) ; - py::enum_(deviceBootloader, "Type") + deviceBootloaderType .value("USB", DeviceBootloader::Type::USB) .value("NETWORK", DeviceBootloader::Type::NETWORK) ; - py::enum_(deviceBootloader, "Memory") + deviceBootloaderMemory .value("FLASH", DeviceBootloader::Memory::FLASH) .value("EMMC", DeviceBootloader::Memory::EMMC) ; - py::enum_(deviceBootloader, "Section") + deviceBootloaderSection .value("HEADER", DeviceBootloader::Section::HEADER) .value("BOOTLOADER", DeviceBootloader::Section::BOOTLOADER) .value("BOOTLOADER_CONFIG", DeviceBootloader::Section::BOOTLOADER_CONFIG) @@ -49,12 +68,13 @@ void DeviceBootloaderBindings::bind(pybind11::module& m){ .def(py::init(), py::arg("deviceDesc"), DOC(dai, DeviceBootloader, DeviceBootloader)) .def(py::init(), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, DeviceBootloader, DeviceBootloader, 2)) - .def("flash", &DeviceBootloader::flash, py::arg("progressCallback"), py::arg("pipeline"), DOC(dai, DeviceBootloader, flash)) - .def("flashDepthaiApplicationPackage", &DeviceBootloader::flashDepthaiApplicationPackage, py::arg("progressCallback"), py::arg("package"), DOC(dai, DeviceBootloader, flashDepthaiApplicationPackage)) - .def("flashBootloader", py::overload_cast, std::string>(&DeviceBootloader::flashBootloader), py::arg("progressCallback"), py::arg("path") = "", DOC(dai, DeviceBootloader, flashBootloader)) - .def("flashBootloader", py::overload_cast, std::string>(&DeviceBootloader::flashBootloader), py::arg("memory"), py::arg("type"), py::arg("progressCallback"), py::arg("path") = "", DOC(dai, DeviceBootloader, flashBootloader, 2)) + .def("flash", [](DeviceBootloader& db, std::function progressCallback, Pipeline& pipeline) { py::gil_scoped_release release; return db.flash(progressCallback, pipeline); }, py::arg("progressCallback"), py::arg("pipeline"), DOC(dai, DeviceBootloader, flash)) + .def("flashDepthaiApplicationPackage", [](DeviceBootloader& db, std::function progressCallback, std::vector package) { py::gil_scoped_release release; return db.flashDepthaiApplicationPackage(progressCallback, package); }, py::arg("progressCallback"), py::arg("package"), DOC(dai, DeviceBootloader, flashDepthaiApplicationPackage)) + .def("flashBootloader", [](DeviceBootloader& db, std::function progressCallback, std::string path) { py::gil_scoped_release release; return db.flashBootloader(progressCallback, path); }, py::arg("progressCallback"), py::arg("path") = "", DOC(dai, DeviceBootloader, flashBootloader)) + .def("flashBootloader", [](DeviceBootloader& db, DeviceBootloader::Memory memory, DeviceBootloader::Type type, std::function progressCallback, std::string path) { py::gil_scoped_release release; return db.flashBootloader(memory, type, progressCallback, path); }, py::arg("memory"), py::arg("type"), py::arg("progressCallback"), py::arg("path") = "", DOC(dai, DeviceBootloader, flashBootloader, 2)) //.def("flashCustom", &DeviceBootloader::flashCustom, py::arg("memory"), py::arg("offset"), py::arg("progressCallback"), py::arg("data"), DOC(dai, DeviceBootloader, flashCustom)) - .def("getVersion", &DeviceBootloader::getVersion, DOC(dai, DeviceBootloader, getVersion)) + .def("getVersion", [](DeviceBootloader& db) { py::gil_scoped_release release; return db.getVersion(); }, DOC(dai, DeviceBootloader, getVersion)) + .def("isEmbeddedVersion", &DeviceBootloader::isEmbeddedVersion, DOC(dai, DeviceBootloader, isEmbeddedVersion)) ; diff --git a/src/DeviceBootloaderBindings.hpp b/src/DeviceBootloaderBindings.hpp index 21883ea96..636a8571d 100644 --- a/src/DeviceBootloaderBindings.hpp +++ b/src/DeviceBootloaderBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct DeviceBootloaderBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/XLinkConnectionBindings.cpp b/src/XLinkConnectionBindings.cpp index d2f77f215..07b9d37cf 100644 --- a/src/XLinkConnectionBindings.cpp +++ b/src/XLinkConnectionBindings.cpp @@ -5,18 +5,41 @@ #include #include -void XLinkConnectionBindings::bind(pybind11::module& m){ +void XLinkConnectionBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; - py::class_(m, "DeviceInfo", DOC(dai, DeviceInfo)) + + // Type definitions + py::class_ deviceInfo(m, "DeviceInfo", DOC(dai, DeviceInfo)); + py::class_ deviceDesc(m, "DeviceDesc"); + py::enum_ xLinkDeviceState(m, "XLinkDeviceState"); + py::enum_ xLinkProtocol(m, "XLinkProtocol"); + py::enum_ xLinkPlatform(m, "XLinkPlatform"); + py::class_> xLinkConnection(m, "XLinkConnection", DOC(dai, XLinkConnection)); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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); + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Bindings + deviceInfo .def(py::init<>()) .def_readwrite("desc", &DeviceInfo::desc) .def_readwrite("state", &DeviceInfo::state) .def("getMxId", &DeviceInfo::getMxId) ; - py::class_(m, "DeviceDesc") + deviceDesc .def(py::init<>()) .def_readwrite("protocol", &deviceDesc_t::protocol) .def_readwrite("platform", &deviceDesc_t::platform) @@ -26,7 +49,7 @@ void XLinkConnectionBindings::bind(pybind11::module& m){ ) ; - py::enum_(m, "XLinkDeviceState") + xLinkDeviceState .value("X_LINK_ANY_STATE", X_LINK_ANY_STATE) .value("X_LINK_BOOTED", X_LINK_BOOTED) .value("X_LINK_UNBOOTED", X_LINK_UNBOOTED) @@ -35,7 +58,7 @@ void XLinkConnectionBindings::bind(pybind11::module& m){ ; - py::enum_(m, "XLinkProtocol") + xLinkProtocol .value("X_LINK_USB_VSC", X_LINK_USB_VSC) .value("X_LINK_USB_CDC", X_LINK_USB_CDC) .value("X_LINK_PCIE", X_LINK_PCIE) @@ -46,14 +69,14 @@ void XLinkConnectionBindings::bind(pybind11::module& m){ .export_values() ; - py::enum_(m, "XLinkPlatform") + xLinkPlatform .value("X_LINK_ANY_PLATFORM", X_LINK_ANY_PLATFORM) .value("X_LINK_MYRIAD_2", X_LINK_MYRIAD_2) .value("X_LINK_MYRIAD_X", X_LINK_MYRIAD_X) .export_values() ; - py::class_(m, "XLinkConnection", DOC(dai, XLinkConnection)) + xLinkConnection .def(py::init>()) .def(py::init()) .def(py::init()) diff --git a/src/XLinkConnectionBindings.hpp b/src/XLinkConnectionBindings.hpp index 5c60527ab..e2a5288f2 100644 --- a/src/XLinkConnectionBindings.hpp +++ b/src/XLinkConnectionBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct XLinkConnectionBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/log/LogBindings.cpp b/src/log/LogBindings.cpp index 3d7449bac..496eaeaa7 100644 --- a/src/log/LogBindings.cpp +++ b/src/log/LogBindings.cpp @@ -3,12 +3,29 @@ // depthai #include "depthai-shared/log/LogLevel.hpp" -void LogBindings::bind(pybind11::module& m){ +void LogBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; // Bind LogLevel - py::enum_(m, "LogLevel") + py::enum_ logLevel(m, "LogLevel"); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + + logLevel .value("TRACE", LogLevel::TRACE) .value("DEBUG", LogLevel::DEBUG) .value("INFO", LogLevel::INFO) @@ -17,5 +34,5 @@ void LogBindings::bind(pybind11::module& m){ .value("CRITICAL", LogLevel::CRITICAL) .value("OFF", LogLevel::OFF) ; - + } \ No newline at end of file diff --git a/src/log/LogBindings.hpp b/src/log/LogBindings.hpp index d64ca2561..06c46a5cf 100644 --- a/src/log/LogBindings.hpp +++ b/src/log/LogBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct LogBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/openvino/OpenVINOBindings.cpp b/src/openvino/OpenVINOBindings.cpp index eca2a0b04..ea7a434d5 100644 --- a/src/openvino/OpenVINOBindings.cpp +++ b/src/openvino/OpenVINOBindings.cpp @@ -3,12 +3,31 @@ // depthai #include "depthai/openvino/OpenVINO.hpp" -void OpenVINOBindings::bind(pybind11::module& m){ +void OpenVINOBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; - // Bind OpenVINO py::class_ openvino(m, "OpenVINO", DOC(dai, OpenVINO)); + py::enum_ openvinoVersion(openvino, "Version", DOC(dai, OpenVINO, Version)); + + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + + + // Bind OpenVINO openvino .def_static("getVersions", &OpenVINO::getVersions, DOC(dai, OpenVINO, getVersions)) .def_static("getVersionName", &OpenVINO::getVersionName, py::arg("version"), DOC(dai, OpenVINO, getVersionName)) @@ -24,7 +43,8 @@ void OpenVINOBindings::bind(pybind11::module& m){ // and that the values are available directly under OpenVINO.VERSION_2021_4, ... // they are exported // By default, pybind creates strong typed enums, eg: OpenVINO::Version::VERSION_2021_4 - py::enum_(openvino, "Version", DOC(dai, OpenVINO, Version)) + + openvinoVersion .value("VERSION_2020_3", OpenVINO::Version::VERSION_2020_3) .value("VERSION_2020_4", OpenVINO::Version::VERSION_2020_4) .value("VERSION_2021_1", OpenVINO::Version::VERSION_2021_1) diff --git a/src/openvino/OpenVINOBindings.hpp b/src/openvino/OpenVINOBindings.hpp index d1353eb71..61e5585a4 100644 --- a/src/openvino/OpenVINOBindings.hpp +++ b/src/openvino/OpenVINOBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct OpenVINOBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; \ No newline at end of file diff --git a/src/pipeline/AssetManagerBindings.cpp b/src/pipeline/AssetManagerBindings.cpp index 902f1d9f1..72b3b29f9 100644 --- a/src/pipeline/AssetManagerBindings.cpp +++ b/src/pipeline/AssetManagerBindings.cpp @@ -3,12 +3,32 @@ // depthai #include "depthai/pipeline/AssetManager.hpp" -void AssetManagerBindings::bind(pybind11::module& m){ +void AssetManagerBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; + + // Type definitions + py::class_> asset(m, "Asset", DOC(dai, Asset)); + py::class_ assetManager(m, "AssetManager", DOC(dai, AssetManager)); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // Bind Asset - py::class_>(m, "Asset", DOC(dai, Asset)) + asset .def(py::init<>()) .def(py::init()) .def_readonly("key", &Asset::key) @@ -23,14 +43,14 @@ void AssetManagerBindings::bind(pybind11::module& m){ .def_readwrite("alignment", &Asset::alignment) ; - // Bind AssetManager - py::class_(m, "AssetManager", DOC(dai, AssetManager)) + assetManager .def(py::init<>()) .def("addExisting", &AssetManager::addExisting, py::arg("assets"), DOC(dai, AssetManager, addExisting)) - .def("add", static_cast(&AssetManager::add), py::arg("asset"), DOC(dai, AssetManager, add)) - .def("add", static_cast(&AssetManager::add), py::arg("key"), py::arg("asset"), DOC(dai, AssetManager, add, 2)) - .def("set", &AssetManager::set, py::arg("key"), py::arg("asset"), DOC(dai, AssetManager, set)) + .def("set", static_cast (AssetManager::*)(Asset)>(&AssetManager::set), py::arg("asset"), DOC(dai, AssetManager, set)) + .def("set", static_cast (AssetManager::*)(const std::string&, Asset)>(&AssetManager::set), py::arg("key"), py::arg("asset"), DOC(dai, AssetManager, set, 2)) + .def("set", static_cast (AssetManager::*)(const std::string& key, const std::string& path, int alignment)>(&AssetManager::set), py::arg("key"), py::arg("path"), py::arg("alignment") = 64, DOC(dai, AssetManager, set, 3)) + .def("set", static_cast (AssetManager::*)(const std::string& key, const std::vector& data, int alignment)>(&AssetManager::set), py::arg("key"), py::arg("data"), py::arg("alignment") = 64, DOC(dai, AssetManager, set, 4)) .def("get", static_cast (AssetManager::*)(const std::string&) const>(&AssetManager::get), py::arg("key"), DOC(dai, AssetManager, get)) .def("get", static_cast (AssetManager::*)(const std::string&)>(&AssetManager::get), py::arg("key"), DOC(dai, AssetManager, get, 2)) .def("getAll", static_cast> (AssetManager::*)() const>(&AssetManager::getAll), DOC(dai, AssetManager, getAll)) @@ -39,4 +59,4 @@ void AssetManagerBindings::bind(pybind11::module& m){ .def("remove", &AssetManager::remove, py::arg("key"), DOC(dai, AssetManager, remove)) ; -} \ No newline at end of file +} diff --git a/src/pipeline/AssetManagerBindings.hpp b/src/pipeline/AssetManagerBindings.hpp index c27dee80c..c46eaf769 100644 --- a/src/pipeline/AssetManagerBindings.hpp +++ b/src/pipeline/AssetManagerBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct AssetManagerBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/pipeline/CommonBindings.cpp b/src/pipeline/CommonBindings.cpp index 905a69558..c77ef27d3 100644 --- a/src/pipeline/CommonBindings.cpp +++ b/src/pipeline/CommonBindings.cpp @@ -7,31 +7,64 @@ #include "depthai-shared/common/MemoryInfo.hpp" #include "depthai-shared/common/ChipTemperature.hpp" #include "depthai-shared/common/CpuUsage.hpp" +#include "depthai-shared/common/ProcessorType.hpp" #include "depthai-shared/common/Timestamp.hpp" #include "depthai-shared/common/Point2f.hpp" #include "depthai-shared/common/Point3f.hpp" #include "depthai-shared/common/Size2f.hpp" #include "depthai-shared/common/UsbSpeed.hpp" -void CommonBindings::bind(pybind11::module& m){ +void CommonBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; - py::class_(m, "Timestamp", DOC(dai, Timestamp)) + py::class_ timestamp(m, "Timestamp", DOC(dai, Timestamp)); + py::class_ point2f(m, "Point2f", DOC(dai, Point2f)); + 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_ cameraImageOrientation(m, "CameraImageOrientation", DOC(dai, CameraImageOrientation)); + py::class_ memoryInfo(m, "MemoryInfo", DOC(dai, MemoryInfo)); + py::class_ chipTemperature(m, "ChipTemperature", DOC(dai, ChipTemperature)); + py::class_ cpuUsage(m, "CpuUsage", DOC(dai, CpuUsage)); + py::enum_ cameraModel(m, "CameraModel", DOC(dai, CameraModel)); + py::class_ stereoRectification(m, "StereoRectification", DOC(dai, StereoRectification)); + py::class_ extrinsics(m, "Extrinsics", DOC(dai, Extrinsics)); + py::class_ cameraInfo(m, "CameraInfo", DOC(dai, CameraInfo)); + py::class_ eepromData(m, "EepromData", DOC(dai, EepromData)); + py::enum_ usbSpeed(m, "UsbSpeed", DOC(dai, UsbSpeed)); + py::enum_ processorType(m, "ProcessorType"); + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + + timestamp .def(py::init<>()) .def_readwrite("sec", &Timestamp::sec) .def_readwrite("nsec", &Timestamp::nsec) .def("get", &Timestamp::get) ; - py::class_(m, "Point2f", DOC(dai, Point2f)) + point2f .def(py::init<>()) .def(py::init()) .def_readwrite("x", &Point2f::x) .def_readwrite("y", &Point2f::y) ; - py::class_(m, "Point3f", DOC(dai, Point3f)) + point3f .def(py::init<>()) .def(py::init()) .def_readwrite("x", &Point3f::x) @@ -39,7 +72,7 @@ void CommonBindings::bind(pybind11::module& m){ .def_readwrite("z", &Point3f::z) ; - py::class_(m, "Size2f", DOC(dai, Size2f)) + size2f .def(py::init<>()) .def(py::init()) .def_readwrite("width", &Size2f::width) @@ -47,7 +80,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // CameraBoardSocket enum bindings - py::enum_(m, "CameraBoardSocket", DOC(dai, CameraBoardSocket)) + cameraBoardSocket .value("AUTO", CameraBoardSocket::AUTO) .value("RGB", CameraBoardSocket::RGB) .value("LEFT", CameraBoardSocket::LEFT) @@ -55,7 +88,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // CameraImageOrientation enum bindings - py::enum_(m, "CameraImageOrientation", DOC(dai, CameraImageOrientation)) + cameraImageOrientation .value("AUTO", CameraImageOrientation::AUTO) .value("NORMAL", CameraImageOrientation::NORMAL) .value("HORIZONTAL_MIRROR", CameraImageOrientation::HORIZONTAL_MIRROR) @@ -64,7 +97,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // MemoryInfo - py::class_(m, "MemoryInfo", DOC(dai, MemoryInfo)) + memoryInfo .def(py::init<>()) .def_readwrite("remaining", &MemoryInfo::remaining) .def_readwrite("used", &MemoryInfo::used) @@ -72,7 +105,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // ChipTemperature - py::class_(m, "ChipTemperature", DOC(dai, ChipTemperature)) + chipTemperature .def(py::init<>()) .def_readwrite("css", &ChipTemperature::css) .def_readwrite("mss", &ChipTemperature::mss) @@ -82,13 +115,13 @@ void CommonBindings::bind(pybind11::module& m){ ; // CpuUsage - py::class_(m, "CpuUsage", DOC(dai, CpuUsage)) + cpuUsage .def(py::init<>()) .def_readwrite("average", &CpuUsage::average) .def_readwrite("msTime", &CpuUsage::msTime) ; // CameraModel enum bindings - py::enum_(m, "CameraModel", DOC(dai, CameraModel)) + cameraModel .value("Perspective", CameraModel::Perspective) .value("Fisheye", CameraModel::Fisheye) .value("Equirectangular", CameraModel::Equirectangular) @@ -96,7 +129,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // StereoRectification - py::class_ (m, "StereoRectification", DOC(dai, StereoRectification)) + stereoRectification .def(py::init<>()) .def_readwrite("rectifiedRotationLeft", &StereoRectification::rectifiedRotationLeft) .def_readwrite("rectifiedRotationRight", &StereoRectification::rectifiedRotationRight) @@ -105,7 +138,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // Extrinsics - py::class_ (m, "Extrinsics", DOC(dai, Extrinsics)) + extrinsics .def(py::init<>()) .def_readwrite("rotationMatrix", &Extrinsics::rotationMatrix) .def_readwrite("translation", &Extrinsics::translation) @@ -114,7 +147,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // CameraInfo - py::class_ (m, "CameraInfo", DOC(dai, CameraInfo)) + cameraInfo .def(py::init<>()) .def_readwrite("width", &CameraInfo::width) .def_readwrite("height", &CameraInfo::height) @@ -126,7 +159,7 @@ void CommonBindings::bind(pybind11::module& m){ ; // EepromData - py::class_ (m, "EepromData", DOC(dai, EepromData)) + eepromData .def(py::init<>()) .def_readwrite("version", &EepromData::version) .def_readwrite("boardName", &EepromData::boardName) @@ -136,7 +169,7 @@ void CommonBindings::bind(pybind11::module& m){ .def_readwrite("imuExtrinsics", &EepromData::imuExtrinsics) ; // UsbSpeed - py::enum_(m, "UsbSpeed", DOC(dai, UsbSpeed)) + usbSpeed .value("UNKNOWN", UsbSpeed::UNKNOWN) .value("LOW", UsbSpeed::LOW) .value("FULL", UsbSpeed::FULL) @@ -145,4 +178,10 @@ void CommonBindings::bind(pybind11::module& m){ .value("SUPER_PLUS", UsbSpeed::SUPER_PLUS) ; + // ProcessorType + processorType + .value("LEON_CSS", ProcessorType::LEON_CSS) + .value("LEON_MSS", ProcessorType::LEON_MSS) + ; + } diff --git a/src/pipeline/CommonBindings.hpp b/src/pipeline/CommonBindings.hpp index a2dab9ace..333b6c112 100644 --- a/src/pipeline/CommonBindings.hpp +++ b/src/pipeline/CommonBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct CommonBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index 3f5213d9e..b54ed085a 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -1,5 +1,6 @@ #include "NodeBindings.hpp" +#include "depthai/pipeline/Pipeline.hpp" #include "depthai/pipeline/Node.hpp" #include "depthai/pipeline/Pipeline.hpp" #include "depthai/pipeline/node/XLinkIn.hpp" @@ -11,8 +12,10 @@ #include "depthai/pipeline/node/VideoEncoder.hpp" #include "depthai/pipeline/node/ImageManip.hpp" #include "depthai/pipeline/node/SPIOut.hpp" +#include "depthai/pipeline/node/SPIIn.hpp" #include "depthai/pipeline/node/DetectionNetwork.hpp" #include "depthai/pipeline/node/SystemLogger.hpp" +#include "depthai/pipeline/node/Script.hpp" #include "depthai/pipeline/node/SpatialLocationCalculator.hpp" #include "depthai/pipeline/node/SpatialDetectionNetwork.hpp" #include "depthai/pipeline/node/ObjectTracker.hpp" @@ -22,19 +25,454 @@ // Libraries #include "hedley/hedley.h" -void NodeBindings::bind(pybind11::module& m){ +// pybind11 +#include "pybind11/stl_bind.h" + +// Map of python node classes and call to pipeline to create it +std::vector(dai::Pipeline&, py::object class_)>>> pyNodeCreateMap; + +py::handle daiNodeModule; + +template +py::class_ addNode(const char* name, const char* docstring = nullptr){ + auto node = py::class_>(daiNodeModule, name, docstring); + pyNodeCreateMap.push_back(std::make_pair(node, [](dai::Pipeline& p, py::object class_){ + return p.create(); + })); + return node; +} + +template +py::class_ addNodeAbstract(const char* name, const char* docstring = nullptr){ + auto node = py::class_>(daiNodeModule, name, docstring); + pyNodeCreateMap.push_back(std::make_pair(node, [](dai::Pipeline& p, py::object class_) -> std::shared_ptr { + throw std::invalid_argument(std::string(py::str(class_)) + " is an abstract node. Choose an appropriate derived node instead"); + return nullptr; + })); + return node; +} + +std::vector(dai::Pipeline&, py::object class_)>>> NodeBindings::getNodeCreateMap(){ + return pyNodeCreateMap; +} + +// Macro helpers +#define ADD_NODE(NodeName) addNode(#NodeName, DOC(dai, node, NodeName)) +#define ADD_NODE_DERIVED(NodeName, Derived) addNode(#NodeName, DOC(dai, node, NodeName)) +#define ADD_NODE_ABSTRACT(NodeName) addNodeAbstract(#NodeName, DOC(dai, node, NodeName)) +#define ADD_NODE_DERIVED_ABSTRACT(NodeName, Derived) addNodeAbstract(#NodeName, DOC(dai, node, NodeName)) +#define ADD_NODE_DOC(NodeName, docstring) addNode(#NodeName, docstring) +#define ADD_NODE_DERIVED_DOC(NodeName, Derived, docstring) addNode(#NodeName, docstring) + + +// Bind map - without init method +template , typename... Args> +py::class_ bindNodeMap(py::handle scope, const std::string &name, Args&&... args) { + using namespace py; + using KeyType = typename Map::key_type; + using MappedType = typename Map::mapped_type; + using Class_ = class_; + + // If either type is a non-module-local bound type then make the map binding non-local as well; + // otherwise (e.g. both types are either module-local or converting) the map will be + // module-local. + auto tinfo = py::detail::get_type_info(typeid(MappedType)); + bool local = !tinfo || tinfo->module_local; + if (local) { + tinfo = py::detail::get_type_info(typeid(KeyType)); + local = !tinfo || tinfo->module_local; + } + + Class_ cl(scope, name.c_str(), pybind11::module_local(local), std::forward(args)...); + + // Register stream insertion operator (if possible) + detail::map_if_insertion_operator(cl, name); + + cl.def("__bool__", + [](const Map &m) -> bool { return !m.empty(); }, + "Check whether the map is nonempty" + ); + + cl.def("__iter__", + [](Map &m) { return make_key_iterator(m.begin(), m.end()); }, + keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + ); + + cl.def("items", + [](Map &m) { return make_iterator(m.begin(), m.end()); }, + keep_alive<0, 1>() /* Essential: keep list alive while iterator exists */ + ); + + // Modified __getitem__. Uses operator[] underneath + cl.def("__getitem__", + [](Map &m, const KeyType &k) -> MappedType & { + return m[k]; + }, + return_value_policy::reference_internal // ref + keepalive + ); + + cl.def("__contains__", + [](Map &m, const KeyType &k) -> bool { + auto it = m.find(k); + if (it == m.end()) + return false; + return true; + } + ); + + // Assignment provided only if the type is copyable + detail::map_assignment(cl); + + cl.def("__delitem__", + [](Map &m, const KeyType &k) { + auto it = m.find(k); + if (it == m.end()) + throw key_error(); + m.erase(it); + } + ); + + cl.def("__len__", &Map::size); + + return cl; +} + + +void NodeBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; + //// Bindings for actual nodes + // Create "namespace" (python submodule) for nodes using namespace dai::node; + // Move properties into nodes and nodes under 'node' submodule + daiNodeModule = m.def_submodule("node"); - - // Base 'Node' class binding + // Properties + py::class_ colorCameraProperties(m, "ColorCameraProperties", DOC(dai, ColorCameraProperties)); + py::enum_ colorCameraPropertiesSensorResolution(colorCameraProperties, "SensorResolution", DOC(dai, ColorCameraProperties, SensorResolution)); + py::enum_ colorCameraPropertiesColorOrder(colorCameraProperties, "ColorOrder", DOC(dai, ColorCameraProperties, ColorOrder)); + py::class_ monoCameraProperties(m, "MonoCameraProperties", DOC(dai, MonoCameraProperties)); + py::enum_ monoCameraPropertiesSensorResolution(monoCameraProperties, "SensorResolution", DOC(dai, MonoCameraProperties, SensorResolution)); + py::class_ stereoDepthProperties(m, "StereoDepthProperties", DOC(dai, StereoDepthProperties)); + py::enum_ medianFilter(m, "MedianFilter", DOC(dai, MedianFilter)); + py::class_ stereoDepthConfigData(m, "StereoDepthConfigData", DOC(dai, StereoDepthConfigData)); + py::class_ videoEncoderProperties(m, "VideoEncoderProperties", DOC(dai, VideoEncoderProperties)); + py::enum_ videoEncoderPropertiesProfile(videoEncoderProperties, "Profile", DOC(dai, VideoEncoderProperties, Profile)); + py::enum_ videoEncoderPropertiesProfileRateControlMode(videoEncoderProperties, "RateControlMode", DOC(dai, VideoEncoderProperties, RateControlMode)); + py::class_ systemLoggerProperties(m, "SystemLoggerProperties", DOC(dai, SystemLoggerProperties)); + py::class_> neuralNetworkProperties(m, "NeuralNetworkProperties", DOC(dai, NeuralNetworkProperties)); + py::class_> detectionNetworkProperties(m, "DetectionNetworkProperties", DOC(dai, DetectionNetworkProperties)); + py::class_> spatialDetectionNetworkProperties(m, "SpatialDetectionNetworkProperties", DOC(dai, SpatialDetectionNetworkProperties)); + py::class_ spatialLocationCalculatorProperties(m, "SpatialLocationCalculatorProperties", DOC(dai, SpatialLocationCalculatorProperties)); + py::enum_ trackerType(m, "TrackerType"); + py::enum_ trackerIdAssigmentPolicy(m, "TrackerIdAssigmentPolicy"); + py::class_> objectTrackerProperties(m, "ObjectTrackerProperties", DOC(dai, ObjectTrackerProperties)); + py::enum_ imuSensor(m, "IMUSensor", DOC(dai, IMUSensor)); + py::class_> imuSensorConfig(m, "IMUSensorConfig", DOC(dai, IMUSensorConfig)); + py::class_ imuProperties(m, "IMUProperties", DOC(dai, IMUProperties)); + py::class_ edgeDetectorProperties(m, "EdgeDetectorProperties", DOC(dai, EdgeDetectorProperties)); + py::class_ spiOutProperties(m, "SPIOutProperties", DOC(dai, SPIOutProperties)); + py::class_ spiInProperties(m, "SPIInProperties", DOC(dai, SPIInProperties)); py::class_> pyNode(m, "Node", DOC(dai, Node)); + py::class_ pyInput(pyNode, "Input", DOC(dai, Node, Input)); + py::enum_ nodeInputType(pyInput, "Type"); + py::class_ pyOutput(pyNode, "Output", DOC(dai, Node, Output)); + py::enum_ nodeOutputType(pyOutput, "Type"); + py::class_ scriptProperties(m, "ScriptProperties", DOC(dai, ScriptProperties)); + + + // Node::Id bindings + py::class_(pyNode, "Id", "Node identificator. Unique for every node on a single Pipeline"); + // Node::Connection bindings + py::class_ nodeConnection(pyNode, "Connection", DOC(dai, Node, Connection)); + // Node::InputMap bindings + bindNodeMap(pyNode, "InputMap"); + // Node::OutputMap bindings + bindNodeMap(pyNode, "OutputMap"); + auto xlinkIn = ADD_NODE(XLinkIn); + auto xlinkOut = ADD_NODE(XLinkOut); + auto colorCamera = ADD_NODE(ColorCamera); + auto neuralNetwork = ADD_NODE(NeuralNetwork); + auto imageManip = ADD_NODE(ImageManip); + auto monoCamera = ADD_NODE(MonoCamera); + auto stereoDepth = ADD_NODE(StereoDepth); + auto videoEncoder = ADD_NODE(VideoEncoder); + auto spiOut = ADD_NODE(SPIOut); + auto spiIn = ADD_NODE(SPIIn); + auto detectionNetwork = ADD_NODE_DERIVED_ABSTRACT(DetectionNetwork, NeuralNetwork); + auto mobileNetDetectionNetwork = ADD_NODE_DERIVED(MobileNetDetectionNetwork, DetectionNetwork); + auto yoloDetectionNetwork = ADD_NODE_DERIVED(YoloDetectionNetwork, DetectionNetwork); + auto spatialDetectionNetwork = ADD_NODE_DERIVED_ABSTRACT(SpatialDetectionNetwork, DetectionNetwork); + auto mobileNetSpatialDetectionNetwork = ADD_NODE_DERIVED(MobileNetSpatialDetectionNetwork, SpatialDetectionNetwork); + auto yoloSpatialDetectionNetwork = ADD_NODE_DERIVED(YoloSpatialDetectionNetwork, SpatialDetectionNetwork); + auto spatialLocationCalculator = ADD_NODE(SpatialLocationCalculator); + auto systemLogger = ADD_NODE(SystemLogger); + auto objectTracker = ADD_NODE(ObjectTracker); + auto script = ADD_NODE(Script); + auto imu = ADD_NODE(IMU); + auto edgeDetector = ADD_NODE(EdgeDetector); + + + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + + + colorCameraPropertiesSensorResolution + .value("THE_1080_P", ColorCameraProperties::SensorResolution::THE_1080_P) + .value("THE_4_K", ColorCameraProperties::SensorResolution::THE_4_K) + .value("THE_12_MP", ColorCameraProperties::SensorResolution::THE_12_MP) + ; + + colorCameraPropertiesColorOrder + .value("BGR", ColorCameraProperties::ColorOrder::BGR) + .value("RGB", ColorCameraProperties::ColorOrder::RGB) + ; + + colorCameraProperties + .def_readwrite("initialControl", &ColorCameraProperties::initialControl) + .def_readwrite("boardSocket", &ColorCameraProperties::boardSocket) + .def_readwrite("colorOrder", &ColorCameraProperties::colorOrder) + .def_readwrite("interleaved", &ColorCameraProperties::interleaved) + .def_readwrite("previewHeight", &ColorCameraProperties::previewHeight) + .def_readwrite("previewWidth", &ColorCameraProperties::previewWidth) + .def_readwrite("videoHeight", &ColorCameraProperties::videoHeight) + .def_readwrite("videoWidth", &ColorCameraProperties::videoWidth) + .def_readwrite("stillHeight", &ColorCameraProperties::stillHeight) + .def_readwrite("stillWidth", &ColorCameraProperties::stillWidth) + .def_readwrite("resolution", &ColorCameraProperties::resolution) + .def_readwrite("fps", &ColorCameraProperties::fps) + .def_readwrite("sensorCropX", &ColorCameraProperties::sensorCropX) + .def_readwrite("sensorCropY", &ColorCameraProperties::sensorCropY) + ; + + // MonoCamera props + + monoCameraPropertiesSensorResolution + .value("THE_720_P", MonoCameraProperties::SensorResolution::THE_720_P) + .value("THE_800_P", MonoCameraProperties::SensorResolution::THE_800_P) + .value("THE_400_P", MonoCameraProperties::SensorResolution::THE_400_P) + ; + + monoCameraProperties + .def_readwrite("initialControl", &MonoCameraProperties::initialControl) + .def_readwrite("boardSocket", &MonoCameraProperties::boardSocket) + .def_readwrite("resolution", &MonoCameraProperties::resolution) + .def_readwrite("fps", &MonoCameraProperties::fps) + ; + + + // StereoDepth props + + // MedianFilter + medianFilter + .value("MEDIAN_OFF", MedianFilter::MEDIAN_OFF) + .value("KERNEL_3x3", MedianFilter::KERNEL_3x3) + .value("KERNEL_5x5", MedianFilter::KERNEL_5x5) + .value("KERNEL_7x7", MedianFilter::KERNEL_7x7) + ; + + stereoDepthProperties + .def_readwrite("calibration", &StereoDepthProperties::calibration) + .def_readwrite("initialConfig", &StereoDepthProperties::initialConfig) + .def_readwrite("inputConfigSync", &StereoDepthProperties::inputConfigSync) + .def_readwrite("depthAlign", &StereoDepthProperties::depthAlign) + .def_readwrite("depthAlignCamera", &StereoDepthProperties::depthAlignCamera) + .def_readwrite("enableLeftRightCheck", &StereoDepthProperties::enableLeftRightCheck) + .def_readwrite("enableSubpixel", &StereoDepthProperties::enableSubpixel) + .def_readwrite("enableExtendedDisparity", &StereoDepthProperties::enableExtendedDisparity) + .def_readwrite("rectifyMirrorFrame", &StereoDepthProperties::rectifyMirrorFrame) + .def_readwrite("rectifyEdgeFillColor", &StereoDepthProperties::rectifyEdgeFillColor) + .def_readwrite("width", &StereoDepthProperties::width) + .def_readwrite("height", &StereoDepthProperties::height) + .def_readwrite("outWidth", &StereoDepthProperties::outWidth, DOC(dai, StereoDepthProperties, outWidth)) + .def_readwrite("outHeight", &StereoDepthProperties::outHeight, DOC(dai, StereoDepthProperties, outHeight)) + .def_readwrite("outKeepAspectRatio", &StereoDepthProperties::outKeepAspectRatio, DOC(dai, StereoDepthProperties, outKeepAspectRatio)) + .def_readwrite("mesh", &StereoDepthProperties::mesh, DOC(dai, StereoDepthProperties, mesh)) + ; + m.attr("StereoDepthProperties").attr("MedianFilter") = medianFilter; + + stereoDepthConfigData + .def(py::init<>()) + .def_readwrite("median", &StereoDepthConfigData::median, DOC(dai, StereoDepthConfigData, median)) + .def_readwrite("confidenceThreshold", &StereoDepthConfigData::confidenceThreshold, DOC(dai, StereoDepthConfigData, confidenceThreshold)) + .def_readwrite("bilateralSigmaValue", &StereoDepthConfigData::bilateralSigmaValue, DOC(dai, StereoDepthConfigData, bilateralSigmaValue)) + .def_readwrite("leftRightCheckThreshold", &StereoDepthConfigData::leftRightCheckThreshold, DOC(dai, StereoDepthConfigData, leftRightCheckThreshold)) + ; + m.attr("StereoDepthConfigData").attr("MedianFilter") = medianFilter; + + + // VideoEncoder props + + videoEncoderPropertiesProfile + .value("H264_BASELINE", VideoEncoderProperties::Profile::H264_BASELINE) + .value("H264_HIGH", VideoEncoderProperties::Profile::H264_HIGH) + .value("H264_MAIN", VideoEncoderProperties::Profile::H264_MAIN) + .value("H265_MAIN", VideoEncoderProperties::Profile::H265_MAIN) + .value("MJPEG", VideoEncoderProperties::Profile::MJPEG) + ; + + videoEncoderPropertiesProfileRateControlMode + .value("CBR", VideoEncoderProperties::RateControlMode::CBR) + .value("VBR", VideoEncoderProperties::RateControlMode::VBR) + ; + + videoEncoderProperties + .def_readwrite("bitrate", &VideoEncoderProperties::bitrate) + .def_readwrite("keyframeFrequency", &VideoEncoderProperties::keyframeFrequency) + .def_readwrite("maxBitrate", &VideoEncoderProperties::maxBitrate) + .def_readwrite("numBFrames", &VideoEncoderProperties::numBFrames) + .def_readwrite("numFramesPool", &VideoEncoderProperties::numFramesPool) + .def_readwrite("profile", &VideoEncoderProperties::profile) + .def_readwrite("quality", &VideoEncoderProperties::quality) + .def_readwrite("rateCtrlMode", &VideoEncoderProperties::rateCtrlMode) + .def_readwrite("width", &VideoEncoderProperties::width) + .def_readwrite("height", &VideoEncoderProperties::height) + ; + + + // System logger + systemLoggerProperties + .def_readwrite("rateHz", &SystemLoggerProperties::rateHz) + ; + + neuralNetworkProperties + .def_readwrite("blobSize", &NeuralNetworkProperties::blobSize) + .def_readwrite("blobUri", &NeuralNetworkProperties::blobUri) + .def_readwrite("numFrames", &NeuralNetworkProperties::numFrames) + .def_readwrite("numThreads", &NeuralNetworkProperties::numThreads) + .def_readwrite("numNCEPerThread", &NeuralNetworkProperties::numNCEPerThread) + ; + + + detectionNetworkProperties + .def_readwrite("nnFamily", &DetectionNetworkProperties::nnFamily) + .def_readwrite("confidenceThreshold", &DetectionNetworkProperties::confidenceThreshold) + .def_readwrite("classes", &DetectionNetworkProperties::classes) + .def_readwrite("coordinates", &DetectionNetworkProperties::coordinates) + .def_readwrite("anchors", &DetectionNetworkProperties::anchors) + .def_readwrite("anchorMasks", &DetectionNetworkProperties::anchorMasks) + .def_readwrite("iouThreshold", &DetectionNetworkProperties::iouThreshold) + ; + + + spatialDetectionNetworkProperties + .def_readwrite("detectedBBScaleFactor", &SpatialDetectionNetworkProperties::detectedBBScaleFactor) + .def_readwrite("depthThresholds", &SpatialDetectionNetworkProperties::depthThresholds) + ; + + spatialLocationCalculatorProperties + .def_readwrite("roiConfig", &SpatialLocationCalculatorProperties::roiConfig) + .def_readwrite("inputConfigSync", &SpatialLocationCalculatorProperties::inputConfigSync) + ; + + + trackerType + .value("ZERO_TERM_IMAGELESS", TrackerType::ZERO_TERM_IMAGELESS) + .value("ZERO_TERM_COLOR_HISTOGRAM", TrackerType::ZERO_TERM_COLOR_HISTOGRAM) + ; + + trackerIdAssigmentPolicy + .value("UNIQUE_ID", TrackerIdAssigmentPolicy::UNIQUE_ID) + .value("SMALLEST_ID", TrackerIdAssigmentPolicy::SMALLEST_ID) + ; + + objectTrackerProperties + .def_readwrite("trackerThreshold", &ObjectTrackerProperties::trackerThreshold) + .def_readwrite("maxObjectsToTrack", &ObjectTrackerProperties::maxObjectsToTrack) + .def_readwrite("detectionLabelsToTrack", &ObjectTrackerProperties::detectionLabelsToTrack) + .def_readwrite("trackerType", &ObjectTrackerProperties::trackerType) + .def_readwrite("trackerIdAssigmentPolicy", &ObjectTrackerProperties::trackerIdAssigmentPolicy) + ; + + // IMU node properties + imuSensor + .value("ACCELEROMETER_RAW", IMUSensor::ACCELEROMETER_RAW, DOC(dai, IMUSensor, ACCELEROMETER_RAW)) + .value("ACCELEROMETER", IMUSensor::ACCELEROMETER, DOC(dai, IMUSensor, ACCELEROMETER)) + .value("LINEAR_ACCELERATION", IMUSensor::LINEAR_ACCELERATION, DOC(dai, IMUSensor, LINEAR_ACCELERATION)) + .value("GRAVITY", IMUSensor::GRAVITY, DOC(dai, IMUSensor, GRAVITY)) + .value("GYROSCOPE_RAW", IMUSensor::GYROSCOPE_RAW, DOC(dai, IMUSensor, GYROSCOPE_RAW)) + .value("GYROSCOPE_CALIBRATED", IMUSensor::GYROSCOPE_CALIBRATED, DOC(dai, IMUSensor, GYROSCOPE_CALIBRATED)) + .value("GYROSCOPE_UNCALIBRATED", IMUSensor::GYROSCOPE_UNCALIBRATED, DOC(dai, IMUSensor, GYROSCOPE_UNCALIBRATED)) + .value("MAGNETOMETER_RAW", IMUSensor::MAGNETOMETER_RAW, DOC(dai, IMUSensor, MAGNETOMETER_RAW)) + .value("MAGNETOMETER_CALIBRATED", IMUSensor::MAGNETOMETER_CALIBRATED, DOC(dai, IMUSensor, MAGNETOMETER_CALIBRATED)) + .value("MAGNETOMETER_UNCALIBRATED", IMUSensor::MAGNETOMETER_UNCALIBRATED, DOC(dai, IMUSensor, MAGNETOMETER_UNCALIBRATED)) + .value("ROTATION_VECTOR", IMUSensor::ROTATION_VECTOR, DOC(dai, IMUSensor, ROTATION_VECTOR)) + .value("GAME_ROTATION_VECTOR", IMUSensor::GAME_ROTATION_VECTOR, DOC(dai, IMUSensor, GAME_ROTATION_VECTOR)) + .value("GEOMAGNETIC_ROTATION_VECTOR", IMUSensor::GEOMAGNETIC_ROTATION_VECTOR, DOC(dai, IMUSensor, GEOMAGNETIC_ROTATION_VECTOR)) + .value("ARVR_STABILIZED_ROTATION_VECTOR", IMUSensor::ARVR_STABILIZED_ROTATION_VECTOR, DOC(dai, IMUSensor, ARVR_STABILIZED_ROTATION_VECTOR)) + .value("ARVR_STABILIZED_GAME_ROTATION_VECTOR", IMUSensor::ARVR_STABILIZED_GAME_ROTATION_VECTOR, DOC(dai, IMUSensor, ARVR_STABILIZED_GAME_ROTATION_VECTOR)) + // .value("GYRO_INTEGRATED_ROTATION_VECTOR", IMUSensor::GYRO_INTEGRATED_ROTATION_VECTOR) + ; + + imuSensorConfig + .def(py::init<>()) + .def_readwrite("sensitivityEnabled", &IMUSensorConfig::sensitivityEnabled) + .def_readwrite("sensitivityRelative", &IMUSensorConfig::sensitivityRelative) + .def_readwrite("changeSensitivity", &IMUSensorConfig::changeSensitivity) + .def_readwrite("reportRate", &IMUSensorConfig::reportRate) + .def_readwrite("sensorId", &IMUSensorConfig::sensorId) + ; + + imuProperties + .def_readwrite("imuSensors", &IMUProperties::imuSensors, DOC(dai, IMUProperties, imuSensors)) + .def_readwrite("batchReportThreshold", &IMUProperties::batchReportThreshold, DOC(dai, IMUProperties, batchReportThreshold)) + .def_readwrite("maxBatchReports", &IMUProperties::maxBatchReports, DOC(dai, IMUProperties, maxBatchReports)) + ; + + // EdgeDetector node properties + edgeDetectorProperties + .def_readwrite("initialConfig", &EdgeDetectorProperties::initialConfig, DOC(dai, EdgeDetectorProperties, initialConfig)) + .def_readwrite("inputConfigSync", &EdgeDetectorProperties::inputConfigSync, DOC(dai, EdgeDetectorProperties, inputConfigSync)) + .def_readwrite("outputFrameSize", &EdgeDetectorProperties::outputFrameSize, DOC(dai, EdgeDetectorProperties, outputFrameSize)) + .def_readwrite("numFramesPool", &EdgeDetectorProperties::numFramesPool, DOC(dai, EdgeDetectorProperties, numFramesPool)) + ; + + // SPIOut properties + spiOutProperties + .def_readwrite("streamName", &SPIOutProperties::streamName) + .def_readwrite("busId", &SPIOutProperties::busId) + ; + + // SPIIn properties + spiInProperties + .def_readwrite("streamName", &SPIInProperties::streamName) + .def_readwrite("busId", &SPIInProperties::busId) + .def_readwrite("maxDataSize", &SPIInProperties::maxDataSize) + .def_readwrite("numFrames", &SPIInProperties::numFrames) + ; + + // Script properties + scriptProperties + .def_readwrite("scriptUri", &ScriptProperties::scriptUri, DOC(dai, ScriptProperties, scriptUri)) + .def_readwrite("scriptName", &ScriptProperties::scriptName, DOC(dai, ScriptProperties, scriptName)) + .def_readwrite("processor", &ScriptProperties::processor, DOC(dai, ScriptProperties, processor)) + ; + + + //////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////// + // Node Bindings after properties, so types are resolved + //////////////////////////////////////////////////////////////////////////////////////// + //////////////////////////////////////////////////////////////////////////////////////// + + // Base 'Node' class binding + // Node::Input bindings - py::class_ pyInput(pyNode, "Input", DOC(dai, Node, Input)); - py::enum_(pyInput, "Type") + nodeInputType .value("SReceiver", Node::Input::Type::SReceiver) .value("MReceiver", Node::Input::Type::MReceiver) ; @@ -48,8 +486,7 @@ void NodeBindings::bind(pybind11::module& m){ ; // Node::Output bindings - py::class_ pyOutput(pyNode, "Output", DOC(dai, Node, Output)); - py::enum_(pyOutput, "Type") + nodeOutputType .value("MSender", Node::Output::Type::MSender) .value("SSender", Node::Output::Type::SSender) ; @@ -59,11 +496,9 @@ void NodeBindings::bind(pybind11::module& m){ .def("unlink", &Node::Output::unlink, py::arg("in"), DOC(dai, Node, Output, unlink)) .def("getConnections", &Node::Output::getConnections, DOC(dai, Node, Output, getConnections)) ; - // Node::Id bindings - py::class_(pyNode, "Id", "Node identificator. Unique for every node on a single Pipeline"); - // Node::Connection bindings - py::class_(pyNode, "Connection", DOC(dai, Node, Connection)) + + nodeConnection .def_property("outputId", [](Node::Connection& conn) { return conn.outputId; }, [](Node::Connection& conn, Node::Id id) {conn.outputId = id; }, DOC(dai, Node, Connection, outputId)) .def_property("outputName", [](Node::Connection& conn) { return conn.outputName; }, [](Node::Connection& conn, std::string name) {conn.outputName = name; }, DOC(dai, Node, Connection, outputName)) .def_property("inputId", [](Node::Connection& conn) { return conn.inputId; }, [](Node::Connection& conn, Node::Id id) {conn.inputId = id; }, DOC(dai, Node, Connection, inputId)) @@ -75,13 +510,14 @@ void NodeBindings::bind(pybind11::module& m){ .def("getName", &Node::getName, DOC(dai, Node, getName)) .def("getOutputs", &Node::getOutputs, DOC(dai, Node, getOutputs)) .def("getInputs", &Node::getInputs, DOC(dai, Node, getInputs)) - .def("getAssets", &Node::getAssets, DOC(dai, Node, getAssets)) .def("getOutputRefs", static_cast (Node::*)()>(&Node::getOutputRefs), DOC(dai, Node, getOutputRefs), py::return_value_policy::reference_internal) .def("getInputRefs", static_cast (Node::*)()>(&Node::getInputRefs), DOC(dai, Node, getInputRefs), py::return_value_policy::reference_internal) .def("getOutputRefs", static_cast (Node::*)() const>(&Node::getOutputRefs), DOC(dai, Node, getOutputRefs), py::return_value_policy::reference_internal) .def("getInputRefs", static_cast (Node::*)() const>(&Node::getInputRefs), DOC(dai, Node, getInputRefs), py::return_value_policy::reference_internal) .def("getParentPipeline", py::overload_cast<>(&Node::getParentPipeline), DOC(dai, Node, getParentPipeline)) .def("getParentPipeline", py::overload_cast<>(&Node::getParentPipeline, py::const_), DOC(dai, Node, getParentPipeline)) + .def("getAssetManager", static_cast(&Node::getAssetManager), py::return_value_policy::reference_internal, DOC(dai, Node, getAssetManager)) + .def("getAssetManager", static_cast(&Node::getAssetManager), py::return_value_policy::reference_internal, DOC(dai, Node, getAssetManager)) ; // MSVC errors out with: @@ -94,10 +530,9 @@ void NodeBindings::bind(pybind11::module& m){ // .def_readwrite("inputName", &dai::Node::Connection::inputName) // ; - //// Bindings for actual nodes // XLinkIn node - py::class_>(m, "XLinkIn", DOC(dai, node, XLinkIn)) + xlinkIn .def_readonly("out", &XLinkIn::out, DOC(dai, node, XLinkIn, out)) .def("setStreamName", &XLinkIn::setStreamName, py::arg("streamName"), DOC(dai, node, XLinkIn, setStreamName)) .def("setMaxDataSize", &XLinkIn::setMaxDataSize, py::arg("maxDataSize"), DOC(dai, node, XLinkIn, setMaxDataSize)) @@ -108,7 +543,7 @@ void NodeBindings::bind(pybind11::module& m){ ; // XLinkOut node - py::class_>(m, "XLinkOut", DOC(dai, node, XLinkOut)) + xlinkOut .def_readonly("input", &XLinkOut::input, DOC(dai, node, XLinkOut, input)) .def("setStreamName", &XLinkOut::setStreamName, py::arg("streamName"), DOC(dai, node, XLinkOut, setStreamName)) .def("setFpsLimit", &XLinkOut::setFpsLimit, py::arg("fpsLimit"), DOC(dai, node, XLinkOut, setFpsLimit)) @@ -119,7 +554,7 @@ void NodeBindings::bind(pybind11::module& m){ ; // ColorCamera node - py::class_>(m, "ColorCamera", DOC(dai, node, ColorCamera)) + colorCamera .def_readonly("inputConfig", &ColorCamera::inputConfig, DOC(dai, node, ColorCamera, inputConfig)) .def_readonly("inputControl", &ColorCamera::inputControl, DOC(dai, node, ColorCamera, inputControl)) .def_readonly("initialControl", &ColorCamera::initialControl, DOC(dai, node, ColorCamera, initialControl)) @@ -193,11 +628,13 @@ void NodeBindings::bind(pybind11::module& m){ .def("getIspWidth", &ColorCamera::getIspWidth, DOC(dai, node, ColorCamera, getIspWidth)) .def("getIspHeight", &ColorCamera::getIspHeight, DOC(dai, node, ColorCamera, getIspHeight)) ; + // ALIAS + daiNodeModule.attr("ColorCamera").attr("Properties") = colorCameraProperties; // NeuralNetwork node - py::class_>(m, "NeuralNetwork", DOC(dai, node, NeuralNetwork)) + neuralNetwork .def_readonly("input", &NeuralNetwork::input, DOC(dai, node, NeuralNetwork, input)) .def_readonly("out", &NeuralNetwork::out, DOC(dai, node, NeuralNetwork, out)) .def_readonly("passthrough", &NeuralNetwork::passthrough, DOC(dai, node, NeuralNetwork, passthrough)) @@ -207,10 +644,12 @@ void NodeBindings::bind(pybind11::module& m){ .def("setNumNCEPerInferenceThread", &NeuralNetwork::setNumNCEPerInferenceThread, py::arg("numNCEPerThread"), DOC(dai, node, NeuralNetwork, setNumNCEPerInferenceThread)) .def("getNumInferenceThreads", &NeuralNetwork::getNumInferenceThreads, DOC(dai, node, NeuralNetwork, getNumInferenceThreads)) ; + // Properties alias + daiNodeModule.attr("NeuralNetwork").attr("Properties") = neuralNetworkProperties; // ImageManip node - py::class_>(m, "ImageManip", DOC(dai, node, ImageManip)) + imageManip .def_readonly("inputConfig", &ImageManip::inputConfig, DOC(dai, node, ImageManip, inputConfig)) .def_readonly("inputImage", &ImageManip::inputImage, DOC(dai, node, ImageManip, inputImage)) .def_readonly("out", &ImageManip::out, DOC(dai, node, ImageManip, out)) @@ -278,7 +717,7 @@ void NodeBindings::bind(pybind11::module& m){ ; // MonoCamera node - py::class_>(m, "MonoCamera", DOC(dai, node, MonoCamera)) + monoCamera .def_readonly("inputControl", &MonoCamera::inputControl, DOC(dai, node, MonoCamera, inputControl)) .def_readonly("out", &MonoCamera::out, DOC(dai, node, MonoCamera, out)) .def_readonly("raw", &MonoCamera::raw, DOC(dai, node, MonoCamera, raw)) @@ -311,11 +750,12 @@ void NodeBindings::bind(pybind11::module& m){ .def("getResolutionWidth", &MonoCamera::getResolutionWidth, DOC(dai, node, MonoCamera, getResolutionWidth)) .def("getResolutionHeight", &MonoCamera::getResolutionHeight, DOC(dai, node, MonoCamera, getResolutionHeight)) ; - + // ALIAS + daiNodeModule.attr("MonoCamera").attr("Properties") = monoCameraProperties; // StereoDepth node - py::class_>(m, "StereoDepth", DOC(dai, node, StereoDepth)) + stereoDepth .def_readonly("initialConfig", &StereoDepth::initialConfig, DOC(dai, node, StereoDepth, initialConfig)) .def_readonly("inputConfig", &StereoDepth::inputConfig, DOC(dai, node, StereoDepth, inputConfig)) .def_readonly("left", &StereoDepth::left, DOC(dai, node, StereoDepth, left)) @@ -395,9 +835,11 @@ void NodeBindings::bind(pybind11::module& m){ }, DOC(dai, node, StereoDepth, setEmptyCalibration)) .def("getMaxDisparity", &StereoDepth::getMaxDisparity, DOC(dai, node, StereoDepth, getMaxDisparity)) ; + // ALIAS + daiNodeModule.attr("StereoDepth").attr("Properties") = stereoDepthProperties; // VideoEncoder node - py::class_>(m, "VideoEncoder", DOC(dai, node, VideoEncoder)) + 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("setDefaultProfilePreset", static_cast(&VideoEncoder::setDefaultProfilePreset), py::arg("width"), py::arg("height"), py::arg("fps"), py::arg("profile"), DOC(dai, node, VideoEncoder, setDefaultProfilePreset)) @@ -429,27 +871,48 @@ void NodeBindings::bind(pybind11::module& m){ .def("getSize", &VideoEncoder::getSize, DOC(dai, node, VideoEncoder, getSize)) .def("getLossless", &VideoEncoder::getLossless, DOC(dai, node, VideoEncoder, getLossless)) ; + // ALIAS + daiNodeModule.attr("VideoEncoder").attr("Properties") = videoEncoderProperties; + - // SPIOut node - py::class_>(m, "SPIOut", DOC(dai, node, SPIOut)) + spiOut .def_readonly("input", &SPIOut::input, DOC(dai, node, SPIOut, input)) .def("setStreamName", &SPIOut::setStreamName, py::arg("name"), DOC(dai, node, SPIOut, setStreamName)) .def("setBusId", &SPIOut::setBusId, py::arg("id"), DOC(dai, node, SPIOut, setBusId)) ; + // ALIAS + daiNodeModule.attr("SPIOut").attr("Properties") = spiOutProperties; + + + // SPIIn node + spiIn + .def_readonly("out", &SPIIn::out, DOC(dai, node, SPIIn, out)) + .def("setStreamName", &SPIIn::setStreamName, py::arg("name"), DOC(dai, node, SPIIn, setStreamName)) + .def("setBusId", &SPIIn::setBusId, py::arg("id"), DOC(dai, node, SPIIn, setBusId)) + .def("setMaxDataSize", &SPIIn::setMaxDataSize, py::arg("maxDataSize"), DOC(dai, node, SPIIn, setMaxDataSize)) + .def("setNumFrames", &SPIIn::setNumFrames, py::arg("numFrames"), DOC(dai, node, SPIIn, setNumFrames)) + .def("getStreamName", &SPIIn::getStreamName, DOC(dai, node, SPIIn, getStreamName)) + .def("getBusId", &SPIIn::getBusId, DOC(dai, node, SPIIn, getBusId)) + .def("getMaxDataSize", &SPIIn::getMaxDataSize, DOC(dai, node, SPIIn, getMaxDataSize)) + .def("getNumFrames", &SPIIn::getNumFrames, DOC(dai, node, SPIIn, getNumFrames)) + ; + // ALIAS + daiNodeModule.attr("SPIIn").attr("Properties") = spiInProperties; - py::class_>(m, "DetectionNetwork", DOC(dai, node, DetectionNetwork)) + // DetectionNetwork node + detectionNetwork .def_readonly("input", &DetectionNetwork::input, DOC(dai, node, DetectionNetwork, input)) .def_readonly("out", &DetectionNetwork::out, DOC(dai, node, DetectionNetwork, out)) .def_readonly("passthrough", &DetectionNetwork::passthrough, DOC(dai, node, DetectionNetwork, passthrough)) .def("setConfidenceThreshold", &DetectionNetwork::setConfidenceThreshold, py::arg("thresh"), DOC(dai, node, DetectionNetwork, setConfidenceThreshold)) ; + // ALIAS + daiNodeModule.attr("DetectionNetwork").attr("Properties") = detectionNetworkProperties; + - // MobileNetDetectionNetwork node - py::class_>(m, "MobileNetDetectionNetwork", DOC(dai, node, MobileNetDetectionNetwork)) - ; // YoloDetectionNetwork node - py::class_>(m, "YoloDetectionNetwork", DOC(dai, node, YoloDetectionNetwork)) + yoloDetectionNetwork .def("setNumClasses", &YoloDetectionNetwork::setNumClasses, py::arg("numClasses"), DOC(dai, node, YoloDetectionNetwork, setNumClasses)) .def("setCoordinateSize", &YoloDetectionNetwork::setCoordinateSize, py::arg("coordinates"), DOC(dai, node, YoloDetectionNetwork, setCoordinateSize)) .def("setAnchors", &YoloDetectionNetwork::setAnchors, py::arg("anchors"), DOC(dai, node, YoloDetectionNetwork, setAnchors)) @@ -457,7 +920,7 @@ void NodeBindings::bind(pybind11::module& m){ .def("setIouThreshold", &YoloDetectionNetwork::setIouThreshold, py::arg("thresh"), DOC(dai, node, YoloDetectionNetwork, setIouThreshold)) ; - py::class_>(m, "SpatialDetectionNetwork", DOC(dai, node, SpatialDetectionNetwork)) + spatialDetectionNetwork .def_readonly("input", &SpatialDetectionNetwork::input, DOC(dai, node, SpatialDetectionNetwork, input)) .def_readonly("inputDepth", &SpatialDetectionNetwork::inputDepth, DOC(dai, node, SpatialDetectionNetwork, inputDepth)) .def_readonly("out", &SpatialDetectionNetwork::out, DOC(dai, node, SpatialDetectionNetwork, out)) @@ -469,12 +932,13 @@ void NodeBindings::bind(pybind11::module& m){ .def("setDepthLowerThreshold", &SpatialDetectionNetwork::setDepthLowerThreshold, py::arg("lowerThreshold"), DOC(dai, node, SpatialDetectionNetwork, setDepthLowerThreshold)) .def("setDepthUpperThreshold", &SpatialDetectionNetwork::setDepthUpperThreshold, py::arg("upperThreshold"), DOC(dai, node, SpatialDetectionNetwork, setDepthUpperThreshold)) ; + // ALIAS + daiNodeModule.attr("SpatialDetectionNetwork").attr("Properties") = spatialDetectionNetworkProperties; - py::class_>(m, "MobileNetSpatialDetectionNetwork", DOC(dai, node, MobileNetSpatialDetectionNetwork)) - ; + // MobileNetSpatialDetectionNetwork // YoloSpatialDetectionNetwork node - py::class_>(m, "YoloSpatialDetectionNetwork", DOC(dai, node, YoloSpatialDetectionNetwork)) + yoloSpatialDetectionNetwork .def("setNumClasses", &YoloSpatialDetectionNetwork::setNumClasses, py::arg("numClasses"), DOC(dai, node, YoloSpatialDetectionNetwork, setNumClasses)) .def("setCoordinateSize", &YoloSpatialDetectionNetwork::setCoordinateSize, py::arg("coordinates"), DOC(dai, node, YoloSpatialDetectionNetwork, setCoordinateSize)) .def("setAnchors", &YoloSpatialDetectionNetwork::setAnchors, py::arg("anchors"), DOC(dai, node, YoloSpatialDetectionNetwork, setAnchors)) @@ -483,7 +947,8 @@ void NodeBindings::bind(pybind11::module& m){ ; // SpatialLocationCalculator node - py::class_>(m, "SpatialLocationCalculator", DOC(dai, node, SpatialLocationCalculator)) + + spatialLocationCalculator .def_readonly("inputConfig", &SpatialLocationCalculator::inputConfig, DOC(dai, node, SpatialLocationCalculator, inputConfig)) .def_readonly("inputDepth", &SpatialLocationCalculator::inputDepth, DOC(dai, node, SpatialLocationCalculator, inputDepth)) .def_readonly("out", &SpatialLocationCalculator::out, DOC(dai, node, SpatialLocationCalculator, out)) @@ -491,15 +956,17 @@ void NodeBindings::bind(pybind11::module& m){ .def_readonly("initialConfig", &SpatialLocationCalculator::initialConfig, DOC(dai, node, SpatialLocationCalculator, initialConfig)) .def("setWaitForConfigInput", &SpatialLocationCalculator::setWaitForConfigInput, py::arg("wait"), DOC(dai, node, SpatialLocationCalculator, setWaitForConfigInput)) ; + // ALIAS + daiNodeModule.attr("SpatialLocationCalculator").attr("Properties") = spatialLocationCalculatorProperties; // SystemLogger node - py::class_>(m, "SystemLogger", DOC(dai, node, SystemLogger)) + systemLogger .def_readonly("out", &SystemLogger::out, DOC(dai, node, SystemLogger, out)) .def("setRate", &SystemLogger::setRate, py::arg("hz"), DOC(dai, node, SystemLogger, setRate)) ; // NeuralNetwork node - py::class_>(m, "ObjectTracker", DOC(dai, node, ObjectTracker)) + objectTracker .def_readonly("inputTrackerFrame", &ObjectTracker::inputTrackerFrame, DOC(dai, node, ObjectTracker, inputTrackerFrame)) .def_readonly("inputDetectionFrame", &ObjectTracker::inputDetectionFrame, DOC(dai, node, ObjectTracker, inputDetectionFrame)) .def_readonly("inputDetections", &ObjectTracker::inputDetections, DOC(dai, node, ObjectTracker, inputDetections)) @@ -514,9 +981,25 @@ void NodeBindings::bind(pybind11::module& m){ .def("setTrackerType", &ObjectTracker::setTrackerType, py::arg("type"), DOC(dai, node, ObjectTracker, setTrackerType)) .def("setTrackerIdAssigmentPolicy", &ObjectTracker::setTrackerIdAssigmentPolicy, py::arg("type"), DOC(dai, node, ObjectTracker, setTrackerIdAssigmentPolicy)) ; + daiNodeModule.attr("ObjectTracker").attr("Properties") = objectTrackerProperties; + + // Script node + script + .def_readonly("inputs", &Script::inputs) + .def_readonly("outputs", &Script::outputs) + .def("setScriptPath", &Script::setScriptPath, DOC(dai, node, Script, setScriptPath)) + .def("setScript", py::overload_cast(&Script::setScript), py::arg("script"), py::arg("name") = "", DOC(dai, node, Script, setScript)) + .def("setScript", py::overload_cast&, const std::string&>(&Script::setScript), py::arg("data"), py::arg("name") = "", DOC(dai, node, Script, setScript, 2)) + .def("getScriptPath", &Script::getScriptPath, DOC(dai, node, Script, getScriptPath)) + .def("getScriptName", &Script::getScriptName, DOC(dai, node, Script, getScriptName)) + .def("setProcessor", &Script::setProcessor, DOC(dai, node, Script, setProcessor)) + .def("getProcessor", &Script::getProcessor, DOC(dai, node, Script, getProcessor)) + ; + daiNodeModule.attr("Script").attr("Properties") = scriptProperties; + // IMU node - py::class_>(m, "IMU", DOC(dai, node, IMU)) + imu .def_readonly("out", &IMU::out, DOC(dai, node, IMU, out)) .def("enableIMUSensor", static_cast(&IMU::enableIMUSensor), py::arg("sensorConfig"), DOC(dai, node, IMU, enableIMUSensor)) .def("enableIMUSensor", static_cast& imuSensors)>(&IMU::enableIMUSensor), py::arg("sensorConfigs"), DOC(dai, node, IMU, enableIMUSensor, 2)) @@ -527,9 +1010,11 @@ void NodeBindings::bind(pybind11::module& m){ .def("setMaxBatchReports", &IMU::setMaxBatchReports, py::arg("maxBatchReports"), DOC(dai, node, IMU, setMaxBatchReports)) .def("getMaxBatchReports", &IMU::getMaxBatchReports, DOC(dai, node, IMU, getMaxBatchReports)) ; + daiNodeModule.attr("IMU").attr("Properties") = imuProperties; // EdgeDetector node - py::class_>(m, "EdgeDetector", DOC(dai, node, EdgeDetector)) + + edgeDetector .def_readonly("initialConfig", &EdgeDetector::initialConfig, DOC(dai, node, EdgeDetector, initialConfig)) .def_readonly("inputConfig", &EdgeDetector::inputConfig, DOC(dai, node, EdgeDetector, inputConfig)) .def_readonly("inputImage", &EdgeDetector::inputImage, DOC(dai, node, EdgeDetector, inputImage)) @@ -538,260 +1023,8 @@ void NodeBindings::bind(pybind11::module& m){ .def("setNumFramesPool", &EdgeDetector::setNumFramesPool, DOC(dai, node, EdgeDetector, setNumFramesPool)) .def("setMaxOutputFrameSize", &EdgeDetector::setMaxOutputFrameSize, DOC(dai, node, EdgeDetector, setMaxOutputFrameSize)) ; - - //////////////////////////////////// - // Node properties bindings - //////////////////////////////////// - py::class_ colorCameraProperties(m, "ColorCameraProperties", DOC(dai, ColorCameraProperties)); - colorCameraProperties - .def_readwrite("initialControl", &ColorCameraProperties::initialControl) - .def_readwrite("boardSocket", &ColorCameraProperties::boardSocket) - .def_readwrite("colorOrder", &ColorCameraProperties::colorOrder) - .def_readwrite("interleaved", &ColorCameraProperties::interleaved) - .def_readwrite("previewHeight", &ColorCameraProperties::previewHeight) - .def_readwrite("previewWidth", &ColorCameraProperties::previewWidth) - .def_readwrite("videoHeight", &ColorCameraProperties::videoHeight) - .def_readwrite("videoWidth", &ColorCameraProperties::videoWidth) - .def_readwrite("stillHeight", &ColorCameraProperties::stillHeight) - .def_readwrite("stillWidth", &ColorCameraProperties::stillWidth) - .def_readwrite("resolution", &ColorCameraProperties::resolution) - .def_readwrite("fps", &ColorCameraProperties::fps) - .def_readwrite("sensorCropX", &ColorCameraProperties::sensorCropX) - .def_readwrite("sensorCropY", &ColorCameraProperties::sensorCropY) - ; - - py::enum_(colorCameraProperties, "SensorResolution", DOC(dai, ColorCameraProperties, SensorResolution)) - .value("THE_1080_P", ColorCameraProperties::SensorResolution::THE_1080_P) - .value("THE_4_K", ColorCameraProperties::SensorResolution::THE_4_K) - .value("THE_12_MP", ColorCameraProperties::SensorResolution::THE_12_MP) - ; - - py::enum_(colorCameraProperties, "ColorOrder", DOC(dai, ColorCameraProperties, ColorOrder)) - .value("BGR", ColorCameraProperties::ColorOrder::BGR) - .value("RGB", ColorCameraProperties::ColorOrder::RGB) - ; - // ALIAS - m.attr("ColorCamera").attr("Properties") = colorCameraProperties; - - - - // MonoCamera props - py::class_ monoCameraProperties(m, "MonoCameraProperties", DOC(dai, MonoCameraProperties)); - monoCameraProperties - .def_readwrite("initialControl", &MonoCameraProperties::initialControl) - .def_readwrite("boardSocket", &MonoCameraProperties::boardSocket) - .def_readwrite("resolution", &MonoCameraProperties::resolution) - .def_readwrite("fps", &MonoCameraProperties::fps) - ; - - py::enum_(monoCameraProperties, "SensorResolution", DOC(dai, MonoCameraProperties, SensorResolution)) - .value("THE_720_P", MonoCameraProperties::SensorResolution::THE_720_P) - .value("THE_800_P", MonoCameraProperties::SensorResolution::THE_800_P) - .value("THE_400_P", MonoCameraProperties::SensorResolution::THE_400_P) - ; - // ALIAS - m.attr("MonoCamera").attr("Properties") = monoCameraProperties; - - - // StereoDepth props - py::class_ stereoDepthProperties(m, "StereoDepthProperties", DOC(dai, StereoDepthProperties)); - stereoDepthProperties - .def_readwrite("calibration", &StereoDepthProperties::calibration) - .def_readwrite("initialConfig", &StereoDepthProperties::initialConfig) - .def_readwrite("inputConfigSync", &StereoDepthProperties::inputConfigSync) - .def_readwrite("depthAlign", &StereoDepthProperties::depthAlign) - .def_readwrite("depthAlignCamera", &StereoDepthProperties::depthAlignCamera) - .def_readwrite("enableLeftRightCheck", &StereoDepthProperties::enableLeftRightCheck) - .def_readwrite("enableSubpixel", &StereoDepthProperties::enableSubpixel) - .def_readwrite("enableExtendedDisparity", &StereoDepthProperties::enableExtendedDisparity) - .def_readwrite("rectifyMirrorFrame", &StereoDepthProperties::rectifyMirrorFrame) - .def_readwrite("rectifyEdgeFillColor", &StereoDepthProperties::rectifyEdgeFillColor) - .def_readwrite("width", &StereoDepthProperties::width) - .def_readwrite("height", &StereoDepthProperties::height) - .def_readwrite("outWidth", &StereoDepthProperties::outWidth, DOC(dai, StereoDepthProperties, outWidth)) - .def_readwrite("outHeight", &StereoDepthProperties::outHeight, DOC(dai, StereoDepthProperties, outHeight)) - .def_readwrite("outKeepAspectRatio", &StereoDepthProperties::outKeepAspectRatio, DOC(dai, StereoDepthProperties, outKeepAspectRatio)) - .def_readwrite("mesh", &StereoDepthProperties::mesh, DOC(dai, StereoDepthProperties, mesh)) - ; - - py::enum_ medianFilter(m, "MedianFilter", DOC(dai, MedianFilter)); - medianFilter - .value("MEDIAN_OFF", MedianFilter::MEDIAN_OFF) - .value("KERNEL_3x3", MedianFilter::KERNEL_3x3) - .value("KERNEL_5x5", MedianFilter::KERNEL_5x5) - .value("KERNEL_7x7", MedianFilter::KERNEL_7x7) - ; - - py::enum_(stereoDepthProperties, "DepthAlign") - .value("RECTIFIED_RIGHT", StereoDepthProperties::DepthAlign::RECTIFIED_RIGHT) - .value("RECTIFIED_LEFT", StereoDepthProperties::DepthAlign::RECTIFIED_LEFT) - .value("CENTER", StereoDepthProperties::DepthAlign::CENTER) - ; - - py::class_ stereoDepthConfigData(m, "StereoDepthConfigData", DOC(dai, StereoDepthConfigData)); - stereoDepthConfigData - .def(py::init<>()) - .def_readwrite("median", &StereoDepthConfigData::median, DOC(dai, StereoDepthConfigData, median)) - .def_readwrite("confidenceThreshold", &StereoDepthConfigData::confidenceThreshold, DOC(dai, StereoDepthConfigData, confidenceThreshold)) - .def_readwrite("bilateralSigmaValue", &StereoDepthConfigData::bilateralSigmaValue, DOC(dai, StereoDepthConfigData, bilateralSigmaValue)) - .def_readwrite("leftRightCheckThreshold", &StereoDepthConfigData::leftRightCheckThreshold, DOC(dai, StereoDepthConfigData, leftRightCheckThreshold)) - ; - - m.attr("StereoDepthProperties").attr("MedianFilter") = medianFilter; - m.attr("StereoDepthConfigData").attr("MedianFilter") = medianFilter; - - // ALIAS - m.attr("StereoDepth").attr("Properties") = stereoDepthProperties; - - - - // VideoEncoder props - py::class_ videoEncoderProperties(m, "VideoEncoderProperties", DOC(dai, VideoEncoderProperties)); - videoEncoderProperties - .def_readwrite("bitrate", &VideoEncoderProperties::bitrate) - .def_readwrite("keyframeFrequency", &VideoEncoderProperties::keyframeFrequency) - .def_readwrite("maxBitrate", &VideoEncoderProperties::maxBitrate) - .def_readwrite("numBFrames", &VideoEncoderProperties::numBFrames) - .def_readwrite("numFramesPool", &VideoEncoderProperties::numFramesPool) - .def_readwrite("profile", &VideoEncoderProperties::profile) - .def_readwrite("quality", &VideoEncoderProperties::quality) - .def_readwrite("rateCtrlMode", &VideoEncoderProperties::rateCtrlMode) - .def_readwrite("width", &VideoEncoderProperties::width) - .def_readwrite("height", &VideoEncoderProperties::height) - ; - - py::enum_(videoEncoderProperties, "Profile", DOC(dai, VideoEncoderProperties, Profile)) - .value("H264_BASELINE", VideoEncoderProperties::Profile::H264_BASELINE) - .value("H264_HIGH", VideoEncoderProperties::Profile::H264_HIGH) - .value("H264_MAIN", VideoEncoderProperties::Profile::H264_MAIN) - .value("H265_MAIN", VideoEncoderProperties::Profile::H265_MAIN) - .value("MJPEG", VideoEncoderProperties::Profile::MJPEG) - ; - - py::enum_(videoEncoderProperties, "RateControlMode", DOC(dai, VideoEncoderProperties, RateControlMode)) - .value("CBR", VideoEncoderProperties::RateControlMode::CBR) - .value("VBR", VideoEncoderProperties::RateControlMode::VBR) - ; - // ALIAS - m.attr("VideoEncoder").attr("Properties") = videoEncoderProperties; - - - - - py::class_(m, "SystemLoggerProperties", DOC(dai, SystemLoggerProperties)) - .def_readwrite("rateHz", &SystemLoggerProperties::rateHz) - ; - - py::class_> neuralNetworkProperties(m, "NeuralNetworkProperties", DOC(dai, NeuralNetworkProperties)); - neuralNetworkProperties - .def_readwrite("blobSize", &NeuralNetworkProperties::blobSize) - .def_readwrite("blobUri", &NeuralNetworkProperties::blobUri) - .def_readwrite("numFrames", &NeuralNetworkProperties::numFrames) - .def_readwrite("numThreads", &NeuralNetworkProperties::numThreads) - .def_readwrite("numNCEPerThread", &NeuralNetworkProperties::numNCEPerThread) - ; - m.attr("NeuralNetwork").attr("Properties") = neuralNetworkProperties; - - - py::class_> detectionNetworkProperties(m, "DetectionNetworkProperties", DOC(dai, DetectionNetworkProperties)); - detectionNetworkProperties - .def_readwrite("nnFamily", &DetectionNetworkProperties::nnFamily) - .def_readwrite("confidenceThreshold", &DetectionNetworkProperties::confidenceThreshold) - .def_readwrite("classes", &DetectionNetworkProperties::classes) - .def_readwrite("coordinates", &DetectionNetworkProperties::coordinates) - .def_readwrite("anchors", &DetectionNetworkProperties::anchors) - .def_readwrite("anchorMasks", &DetectionNetworkProperties::anchorMasks) - .def_readwrite("iouThreshold", &DetectionNetworkProperties::iouThreshold) - ; - // ALIAS - m.attr("DetectionNetwork").attr("Properties") = detectionNetworkProperties; - - - py::class_> spatialDetectionNetworkProperties(m, "SpatialDetectionNetworkProperties", DOC(dai, SpatialDetectionNetworkProperties)); - spatialDetectionNetworkProperties - .def_readwrite("detectedBBScaleFactor", &SpatialDetectionNetworkProperties::detectedBBScaleFactor) - .def_readwrite("depthThresholds", &SpatialDetectionNetworkProperties::depthThresholds) - ; - // ALIAS - m.attr("SpatialDetectionNetwork").attr("Properties") = spatialDetectionNetworkProperties; - - - py::class_ spatialLocationCalculatorProperties(m, "SpatialLocationCalculatorProperties", DOC(dai, SpatialLocationCalculatorProperties)); - spatialLocationCalculatorProperties - .def_readwrite("roiConfig", &SpatialLocationCalculatorProperties::roiConfig) - .def_readwrite("inputConfigSync", &SpatialLocationCalculatorProperties::inputConfigSync) - ; - m.attr("SpatialLocationCalculator").attr("Properties") = spatialLocationCalculatorProperties; - - - py::enum_(m, "TrackerType") - .value("ZERO_TERM_IMAGELESS", TrackerType::ZERO_TERM_IMAGELESS) - .value("ZERO_TERM_COLOR_HISTOGRAM", TrackerType::ZERO_TERM_COLOR_HISTOGRAM) - ; - - py::enum_(m, "TrackerIdAssigmentPolicy") - .value("UNIQUE_ID", TrackerIdAssigmentPolicy::UNIQUE_ID) - .value("SMALLEST_ID", TrackerIdAssigmentPolicy::SMALLEST_ID) - ; - - - py::class_> objectTrackerProperties(m, "ObjectTrackerProperties", DOC(dai, ObjectTrackerProperties)); - objectTrackerProperties - .def_readwrite("trackerThreshold", &ObjectTrackerProperties::trackerThreshold) - .def_readwrite("maxObjectsToTrack", &ObjectTrackerProperties::maxObjectsToTrack) - .def_readwrite("detectionLabelsToTrack", &ObjectTrackerProperties::detectionLabelsToTrack) - .def_readwrite("trackerType", &ObjectTrackerProperties::trackerType) - .def_readwrite("trackerIdAssigmentPolicy", &ObjectTrackerProperties::trackerIdAssigmentPolicy) - ; - m.attr("ObjectTracker").attr("Properties") = objectTrackerProperties; - - py::enum_(m, "IMUSensor", DOC(dai, IMUSensor)) - .value("ACCELEROMETER_RAW", IMUSensor::ACCELEROMETER_RAW, DOC(dai, IMUSensor, ACCELEROMETER_RAW)) - .value("ACCELEROMETER", IMUSensor::ACCELEROMETER, DOC(dai, IMUSensor, ACCELEROMETER)) - .value("LINEAR_ACCELERATION", IMUSensor::LINEAR_ACCELERATION, DOC(dai, IMUSensor, LINEAR_ACCELERATION)) - .value("GRAVITY", IMUSensor::GRAVITY, DOC(dai, IMUSensor, GRAVITY)) - .value("GYROSCOPE_RAW", IMUSensor::GYROSCOPE_RAW, DOC(dai, IMUSensor, GYROSCOPE_RAW)) - .value("GYROSCOPE_CALIBRATED", IMUSensor::GYROSCOPE_CALIBRATED, DOC(dai, IMUSensor, GYROSCOPE_CALIBRATED)) - .value("GYROSCOPE_UNCALIBRATED", IMUSensor::GYROSCOPE_UNCALIBRATED, DOC(dai, IMUSensor, GYROSCOPE_UNCALIBRATED)) - .value("MAGNETOMETER_RAW", IMUSensor::MAGNETOMETER_RAW, DOC(dai, IMUSensor, MAGNETOMETER_RAW)) - .value("MAGNETOMETER_CALIBRATED", IMUSensor::MAGNETOMETER_CALIBRATED, DOC(dai, IMUSensor, MAGNETOMETER_CALIBRATED)) - .value("MAGNETOMETER_UNCALIBRATED", IMUSensor::MAGNETOMETER_UNCALIBRATED, DOC(dai, IMUSensor, MAGNETOMETER_UNCALIBRATED)) - .value("ROTATION_VECTOR", IMUSensor::ROTATION_VECTOR, DOC(dai, IMUSensor, ROTATION_VECTOR)) - .value("GAME_ROTATION_VECTOR", IMUSensor::GAME_ROTATION_VECTOR, DOC(dai, IMUSensor, GAME_ROTATION_VECTOR)) - .value("GEOMAGNETIC_ROTATION_VECTOR", IMUSensor::GEOMAGNETIC_ROTATION_VECTOR, DOC(dai, IMUSensor, GEOMAGNETIC_ROTATION_VECTOR)) - .value("ARVR_STABILIZED_ROTATION_VECTOR", IMUSensor::ARVR_STABILIZED_ROTATION_VECTOR, DOC(dai, IMUSensor, ARVR_STABILIZED_ROTATION_VECTOR)) - .value("ARVR_STABILIZED_GAME_ROTATION_VECTOR", IMUSensor::ARVR_STABILIZED_GAME_ROTATION_VECTOR, DOC(dai, IMUSensor, ARVR_STABILIZED_GAME_ROTATION_VECTOR)) - // .value("GYRO_INTEGRATED_ROTATION_VECTOR", IMUSensor::GYRO_INTEGRATED_ROTATION_VECTOR) - ; - - py::class_>(m, "IMUSensorConfig", DOC(dai, IMUSensorConfig)) - .def(py::init<>()) - .def_readwrite("sensitivityEnabled", &IMUSensorConfig::sensitivityEnabled) - .def_readwrite("sensitivityRelative", &IMUSensorConfig::sensitivityRelative) - .def_readwrite("changeSensitivity", &IMUSensorConfig::changeSensitivity) - .def_readwrite("reportRate", &IMUSensorConfig::reportRate) - .def_readwrite("sensorId", &IMUSensorConfig::sensorId) - ; - - py::class_ imuProperties(m, "IMUProperties", DOC(dai, IMUProperties)); - imuProperties - .def_readwrite("imuSensors", &IMUProperties::imuSensors, DOC(dai, IMUProperties, imuSensors)) - .def_readwrite("batchReportThreshold", &IMUProperties::batchReportThreshold, DOC(dai, IMUProperties, batchReportThreshold)) - .def_readwrite("maxBatchReports", &IMUProperties::maxBatchReports, DOC(dai, IMUProperties, maxBatchReports)) - ; - m.attr("IMU").attr("Properties") = imuProperties; - - - py::class_ edgeDetectorProperties(m, "EdgeDetectorProperties", DOC(dai, EdgeDetectorProperties)); - edgeDetectorProperties - .def_readwrite("initialConfig", &EdgeDetectorProperties::initialConfig, DOC(dai, EdgeDetectorProperties, initialConfig)) - .def_readwrite("inputConfigSync", &EdgeDetectorProperties::inputConfigSync, DOC(dai, EdgeDetectorProperties, inputConfigSync)) - .def_readwrite("outputFrameSize", &EdgeDetectorProperties::outputFrameSize, DOC(dai, EdgeDetectorProperties, outputFrameSize)) - .def_readwrite("numFramesPool", &EdgeDetectorProperties::numFramesPool, DOC(dai, EdgeDetectorProperties, numFramesPool)) - - ; - m.attr("EdgeDetector").attr("Properties") = edgeDetectorProperties; - + daiNodeModule.attr("EdgeDetector").attr("Properties") = edgeDetectorProperties; } + diff --git a/src/pipeline/NodeBindings.hpp b/src/pipeline/NodeBindings.hpp index 9149a0aad..bd3b1994b 100644 --- a/src/pipeline/NodeBindings.hpp +++ b/src/pipeline/NodeBindings.hpp @@ -7,5 +7,6 @@ #include "depthai/pipeline/Node.hpp" struct NodeBindings : public dai::Node { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); + static std::vector(dai::Pipeline&, py::object class_)>>> getNodeCreateMap(); }; diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index 193f762b4..4583bf9ab 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -1,4 +1,6 @@ + #include "PipelineBindings.hpp" +#include "NodeBindings.hpp" // depthai #include "depthai/pipeline/Pipeline.hpp" @@ -10,10 +12,12 @@ #include "depthai/pipeline/node/ColorCamera.hpp" #include "depthai/pipeline/node/VideoEncoder.hpp" #include "depthai/pipeline/node/SPIOut.hpp" +#include "depthai/pipeline/node/SPIIn.hpp" #include "depthai/pipeline/node/ImageManip.hpp" #include "depthai/pipeline/node/MonoCamera.hpp" #include "depthai/pipeline/node/StereoDepth.hpp" #include "depthai/pipeline/node/DetectionNetwork.hpp" +#include "depthai/pipeline/node/Script.hpp" #include "depthai/pipeline/node/SystemLogger.hpp" #include "depthai/pipeline/node/SpatialLocationCalculator.hpp" #include "depthai/pipeline/node/SpatialDetectionNetwork.hpp" @@ -24,13 +28,43 @@ // depthai-shared #include "depthai-shared/properties/GlobalProperties.hpp" -void PipelineBindings::bind(pybind11::module& m){ + +std::shared_ptr createNode(dai::Pipeline& p, py::object class_){ + auto nodeCreateMap = NodeBindings::getNodeCreateMap(); + for(auto& kv : nodeCreateMap){ + auto& node = kv.first; + auto& create = kv.second; + if(node.is(class_)){ + return create(p, class_); + } + } + return nullptr; +} + +void PipelineBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; + // Type definitions + py::class_ globalProperties(m, "GlobalProperties", DOC(dai, GlobalProperties)); + py::class_ pipeline(m, "Pipeline", DOC(dai, Pipeline, 2)); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // 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 + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // Bind global properties - py::class_(m, "GlobalProperties", DOC(dai, GlobalProperties)) + globalProperties .def_readwrite("leonOsFrequencyHz", &GlobalProperties::leonCssFrequencyHz) .def_readwrite("leonRtFrequencyHz", &GlobalProperties::leonMssFrequencyHz) .def_readwrite("pipelineName", &GlobalProperties::pipelineName) @@ -40,7 +74,7 @@ void PipelineBindings::bind(pybind11::module& m){ ; // bind pipeline - py::class_(m, "Pipeline", DOC(dai, Pipeline, 2)) + pipeline .def(py::init<>(), DOC(dai, Pipeline, Pipeline)) //.def(py::init()) .def("getGlobalProperties", &Pipeline::getGlobalProperties, DOC(dai, Pipeline, getGlobalProperties)) @@ -55,7 +89,6 @@ void PipelineBindings::bind(pybind11::module& m){ .def("getNodeMap", &Pipeline::getNodeMap, DOC(dai, Pipeline, getNodeMap), py::return_value_policy::reference_internal, DOC(dai, Pipeline, getNodeMap)) .def("link", &Pipeline::link, DOC(dai, Pipeline, link), DOC(dai, Pipeline, link)) .def("unlink", &Pipeline::unlink, DOC(dai, Pipeline, unlink), DOC(dai, Pipeline, unlink)) - .def("getAllAssets", &Pipeline::getAllAssets, DOC(dai, Pipeline, getAllAssets)) .def("getAssetManager", static_cast(&Pipeline::getAssetManager), py::return_value_policy::reference_internal, DOC(dai, Pipeline, getAssetManager)) .def("getAssetManager", static_cast(&Pipeline::getAssetManager), py::return_value_policy::reference_internal, DOC(dai, Pipeline, getAssetManager)) .def("setOpenVINOVersion", &Pipeline::setOpenVINOVersion, py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Pipeline, setOpenVINOVersion)) @@ -63,13 +96,23 @@ void PipelineBindings::bind(pybind11::module& m){ .def("setCameraTuningBlobPath", &Pipeline::setCameraTuningBlobPath, py::arg("path"), DOC(dai, Pipeline, setCameraTuningBlobPath)) .def("setCalibrationData", &Pipeline::setCalibrationData, py::arg("calibrationDataHandler"), DOC(dai, Pipeline, setCalibrationData)) .def("getCalibrationData", &Pipeline::getCalibrationData, DOC(dai, Pipeline, getCalibrationData)) - // templated create function + // 'Template' create function + .def("create", [](dai::Pipeline& p, py::object class_) { + auto node = createNode(p, class_); + if(node == nullptr){ + throw std::invalid_argument(std::string(py::str(class_)) + " is not a subclass of depthai.node"); + } + return node; + }) + // TODO(themarpe) DEPRECATE, use pipeline.create([class name]) + // templated create function .def("createXLinkIn", &Pipeline::create) .def("createXLinkOut", &Pipeline::create) .def("createNeuralNetwork", &Pipeline::create) .def("createColorCamera", &Pipeline::create) .def("createVideoEncoder", &Pipeline::create) .def("createSPIOut", &Pipeline::create) + .def("createSPIIn", &Pipeline::create) .def("createImageManip", &Pipeline::create) .def("createMonoCamera", &Pipeline::create) .def("createStereoDepth", &Pipeline::create) diff --git a/src/pipeline/PipelineBindings.hpp b/src/pipeline/PipelineBindings.hpp index 9df795126..3e759ddd8 100644 --- a/src/pipeline/PipelineBindings.hpp +++ b/src/pipeline/PipelineBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct PipelineBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; diff --git a/src/py_bindings.cpp b/src/py_bindings.cpp index 223a20873..75bcf9ec7 100644 --- a/src/py_bindings.cpp +++ b/src/py_bindings.cpp @@ -38,21 +38,26 @@ PYBIND11_MODULE(depthai,m) m.attr("__commit_datetime__") = DEPTHAI_PYTHON_COMMIT_DATETIME; m.attr("__build_datetime__") = DEPTHAI_PYTHON_BUILD_DATETIME; - // Add bindings - OpenVINOBindings::bind(m); - AssetManagerBindings::bind(m); - NodeBindings::bind(m); - PipelineBindings::bind(m); - XLinkConnectionBindings::bind(m); - DeviceBindings::bind(m); - CommonBindings::bind(m); - CalibrationHandlerBindings::bind(m); - DeviceBootloaderBindings::bind(m); - - DatatypeBindings::bind(m); - DataQueueBindings::bind(m); - LogBindings::bind(m); + std::deque callstack; + callstack.push_front(&DatatypeBindings::bind); + callstack.push_front(&LogBindings::bind); + callstack.push_front(&DataQueueBindings::bind); + callstack.push_front(&OpenVINOBindings::bind); + callstack.push_front(&AssetManagerBindings::bind); + callstack.push_front(&NodeBindings::bind); + callstack.push_front(&PipelineBindings::bind); + callstack.push_front(&XLinkConnectionBindings::bind); + callstack.push_front(&DeviceBindings::bind); + callstack.push_front(&DeviceBootloaderBindings::bind); + callstack.push_front(&CalibrationHandlerBindings::bind); + // end of the callstack + callstack.push_front([](py::module&, void*){}); + + Callstack callstackAdapter(callstack); + + // Initial call + CommonBindings::bind(m, &callstackAdapter); // Call dai::initialize on 'import depthai' to initialize asap with additional information to print dai::initialize(std::string("Python bindings - version: ") + DEPTHAI_PYTHON_VERSION + " from " + DEPTHAI_PYTHON_COMMIT_DATETIME + " build: " + DEPTHAI_PYTHON_BUILD_DATETIME); diff --git a/src/pybind11_common.hpp b/src/pybind11_common.hpp index 8add9f012..8fbab8dd8 100644 --- a/src/pybind11_common.hpp +++ b/src/pybind11_common.hpp @@ -10,6 +10,7 @@ #include #include #include +#include // Include docstring file #include "docstring.hpp" @@ -24,4 +25,6 @@ namespace pybind11 { namespace detail { namespace py = pybind11; +using StackFunction = void (*)(pybind11::module &m, void *pCallstack); +using Callstack = std::stack; diff --git a/src/utility/ResourcesBindings.cpp b/src/utility/ResourcesBindings.cpp index dd6d4c8df..0c87866ce 100644 --- a/src/utility/ResourcesBindings.cpp +++ b/src/utility/ResourcesBindings.cpp @@ -3,13 +3,13 @@ // depthai // include resources #include "depthai/" -void ResourcesBindings::bind(pybind11::module& m){ +void ResourcesBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; // Bind Resources (if needed) py::class_>(m, "Resources") - .def(py::init([](){ + .def(py::init([](){ return std::unique_ptr>(&Resources::getInstance()); }); diff --git a/src/utility/ResourcesBindings.hpp b/src/utility/ResourcesBindings.hpp index e5af26db1..ac36b73db 100644 --- a/src/utility/ResourcesBindings.hpp +++ b/src/utility/ResourcesBindings.hpp @@ -4,5 +4,5 @@ #include "pybind11_common.hpp" struct ResourcesBindings { - static void bind(pybind11::module& m); + static void bind(pybind11::module& m, void* pCallstack); }; \ No newline at end of file