diff --git a/.gitignore b/.gitignore index aac452dce..f9f99db0f 100644 --- a/.gitignore +++ b/.gitignore @@ -25,9 +25,10 @@ _builds/ #git *.orig +*_REMOTE_* +*_LOCAL_* +*_BACKUP_* +*_BASE_* #ci wheelhouse/ - -# Example blobs/files -examples/models/ \ No newline at end of file diff --git a/README.md b/README.md index 60c71d6cb..ce8e6ad90 100644 --- a/README.md +++ b/README.md @@ -33,6 +33,7 @@ See: [depthai-core dependencies](https://github.com/luxonis/depthai-core#depende To build a shared library from source perform the following: ``` +git submodule update --init --recursive mkdir build && cd build cmake .. [-D PYTHON_EXECUTABLE=/full/path/to/python] cmake --build . --parallel @@ -54,6 +55,7 @@ python3 -m pip install . To run the tests build the library with the following options ``` +git submodule update --init --recursive mkdir build_tests && cd build_tests cmake .. -D DEPTHAI_PYTHON_ENABLE_TESTS=ON -D DEPTHAI_PYTHON_ENABLE_EXAMPLES=ON -D DEPTHAI_PYTHON_TEST_EXAMPLES=ON cmake --build . --parallel @@ -68,7 +70,6 @@ ctest - Raspbian 10; - macOS 10.14.6, 10.15.4; - ### Building documentation - **Using [Docker](https://docs.docker.com/) (with [Docker Compose](https://docs.docker.com/compose/install/))** @@ -78,19 +79,18 @@ ctest sudo docker-compose build sudo docker-compose up ``` - - > ℹ️ You can leave out the `sudo` if you have added your user to the `docker` group (or are using rootless docker). + > ℹ️ You can leave out the `sudo` if you have added your user to the `docker` group (or are using rootless docker). Then open [http://localhost:8000](http://localhost:8000). - + This docker container will watch changes in the `docs/source` directory and rebuild the docs automatically - **Linux** - + First, please install the required [dependencies](#Dependencies) - + Then run the following commands to build the docs website - + ``` python3 -m pip install -U pip python3 -m pip install -r docs/requirements.txt @@ -98,16 +98,16 @@ ctest cmake --build build --parallel --target sphinx python3 -m http.server --bind 0.0.0.0 8000 --directory build/docs/sphinx ``` - + Then open [http://localhost:8000](http://localhost:8000). This will build documentation based on current sources, so if some new changes will be made, run this command in a new terminal window to update the website source - + ``` cmake --build build --parallel --target sphinx ``` - + Then refresh your page - it should load the updated website that was just built ## Troubleshooting @@ -121,7 +121,7 @@ Build failure on Ubuntu 18.04 ("relocation ..." link error) with gcc 7.4.0 (defa sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-8 70 sudo update-alternatives --install /usr/bin/g++ g++ /usr/bin/g++-8 70 ### Hunter -Hunter is a CMake-only dependency manager for C/C++ projects. +Hunter is a CMake-only dependency manager for C/C++ projects. If you are stuck with error message which mentions external libraries (subdirectory of `.hunter`) like the following: ``` @@ -145,7 +145,7 @@ del C:/[user]/.hunter ### LTO - link time optimization -If following message appears: +If following message appears: ``` lto1: internal compiler error: in add_symbol_to_partition_1, at lto/lto-partition.c:152 Please submit a full bug report, diff --git a/depthai-core b/depthai-core index 06dcfd5da..acdded348 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 06dcfd5daab08591a58811763c8bd28c22c0ca7f +Subproject commit acdded3484b75b04925434b1fec7777f7d060d22 diff --git a/docs/source/index.rst b/docs/source/index.rst index d9a8cd303..b11e2f15f 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -85,7 +85,9 @@ Now, pick a tutorial or code sample and start utilizing Gen2 capabilities samples/11_rgb_encoding_mono_mobilenet.rst samples/12_rgb_encoding_mono_mobilenet_depth.rst samples/13_encoding_max_limit.rst - samples/14_color_camera_control.rst + samples/14_1_color_camera_control.rst + samples/14_2_mono_camera_control.rst + samples/14_3_depth_crop_control.rst samples/15_rgb_mobilenet_4k.rst samples/16_device_queue_event.rst samples/17_video_mobilenet.rst @@ -102,6 +104,10 @@ Now, pick a tutorial or code sample and start utilizing Gen2 capabilities samples/26_3_spatial_tiny_yolo.rst samples/27_spatial_location_calculator.rst samples/28_camera_video_example.rst + samples/29_1_object_tracker.rst + samples/29_2_spatial_object_tracker.rst + samples/29_3_object_tracker_video.rst + samples/30_stereo_depth_from_host.rst .. toctree:: :maxdepth: 1 diff --git a/docs/source/samples/09_mono_mobilenet.rst b/docs/source/samples/09_mono_mobilenet.rst index 8e6d367d7..4535fc493 100644 --- a/docs/source/samples/09_mono_mobilenet.rst +++ b/docs/source/samples/09_mono_mobilenet.rst @@ -10,7 +10,7 @@ Demo .. raw:: html
- +
Setup diff --git a/docs/source/samples/10_mono_depth_mobilenetssd.rst b/docs/source/samples/10_mono_depth_mobilenetssd.rst index aac1c1bba..c6095dc50 100644 --- a/docs/source/samples/10_mono_depth_mobilenetssd.rst +++ b/docs/source/samples/10_mono_depth_mobilenetssd.rst @@ -1,5 +1,5 @@ -10 - Mono & MobilenetSSD & Encoding -=================================== +10 - Mono & MobilenetSSD & Depth +================================ This example shows how to run MobileNetv2SSD on the left grayscale camera in parallel with running the disparity depth results, displaying both the depth map and the right grayscale stream, with the @@ -11,7 +11,7 @@ Demo .. raw:: html
- +
Setup diff --git a/docs/source/samples/11_rgb_encoding_mono_mobilenet.rst b/docs/source/samples/11_rgb_encoding_mono_mobilenet.rst index a870d4145..15259c3db 100644 --- a/docs/source/samples/11_rgb_encoding_mono_mobilenet.rst +++ b/docs/source/samples/11_rgb_encoding_mono_mobilenet.rst @@ -18,7 +18,7 @@ Demo .. raw:: html
- +
Setup diff --git a/docs/source/samples/12_rgb_encoding_mono_mobilenet_depth.rst b/docs/source/samples/12_rgb_encoding_mono_mobilenet_depth.rst index c7abff6f7..107170302 100644 --- a/docs/source/samples/12_rgb_encoding_mono_mobilenet_depth.rst +++ b/docs/source/samples/12_rgb_encoding_mono_mobilenet_depth.rst @@ -20,7 +20,7 @@ Demo .. raw:: html
- +
Setup diff --git a/docs/source/samples/14_color_camera_control.rst b/docs/source/samples/14_1_color_camera_control.rst similarity index 68% rename from docs/source/samples/14_color_camera_control.rst rename to docs/source/samples/14_1_color_camera_control.rst index 2660b763c..f74c811fb 100644 --- a/docs/source/samples/14_color_camera_control.rst +++ b/docs/source/samples/14_1_color_camera_control.rst @@ -1,5 +1,5 @@ -14 - Color Camera Control -========================= +14.1 - Color Camera Control +=========================== This example shows how to controll the device-side crop and camera triggers. An output is a displayed RGB cropped frame, that can be manipulated using the following keys: @@ -9,6 +9,12 @@ An output is a displayed RGB cropped frame, that can be manipulated using the fo #. `w` will move the crop up #. `s` will move the crop down #. `c` will trigger a `still` event, causing the current frame to be captured and sent over `still` output from camera node +#. `t` will trigger autofocus +#. `f` will trigger autofocus continuously +#. `e` will trigger autoexposure +#. `i` and `o` will decrease/increase the exposure time +#. `k` and `l` will decrease/increase the sensitivity iso +#. `,` and `.` will decrease/increase the focus range Demo #### @@ -27,9 +33,9 @@ Setup Source code ########### -Also `available on GitHub `__ +Also `available on GitHub `__ -.. literalinclude:: ../../../examples/14_color_camera_control.py +.. literalinclude:: ../../../examples/14_1_color_camera_control.py :language: python :linenos: diff --git a/docs/source/samples/14_2_mono_camera_control.rst b/docs/source/samples/14_2_mono_camera_control.rst new file mode 100644 index 000000000..5af8724b7 --- /dev/null +++ b/docs/source/samples/14_2_mono_camera_control.rst @@ -0,0 +1,34 @@ +14.2 - Mono Camera Control +========================== + +This example shows how to controll the device-side crop and camera triggers. +TWo output is a displayed mono cropped frame, that can be manipulated using the following keys: + +#. `a` will move the crop left +#. `d` will move the crop right +#. `w` will move the crop up +#. `s` will move the crop down +#. `e` will trigger autoexposure +#. `i` and `o` will decrease/increase the exposure time +#. `k` and `l` will decrease/increase the sensitivity iso + + +Demo +#### + + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + +Source code +########### + +Also `available on GitHub `__ + +.. literalinclude:: ../../../examples/14_2_mono_camera_control.py + :language: python + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/samples/14_3_depth_crop_control.rst b/docs/source/samples/14_3_depth_crop_control.rst new file mode 100644 index 000000000..3e46b58a3 --- /dev/null +++ b/docs/source/samples/14_3_depth_crop_control.rst @@ -0,0 +1,31 @@ +14.3 - Depth Crop Control +========================= + +This example shows usage of depth camera in crop mode with the possibility to move the crop. +You can manipulate the movement of the cropped frame by using the following keys: + +#. `a` will move the crop left +#. `d` will move the crop right +#. `w` will move the crop up +#. `s` will move the crop down + + +Demo +#### + + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + +Source code +########### + +Also `available on GitHub `__ + +.. literalinclude:: ../../../examples/14_3_depth_crop_control.py + :language: python + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/samples/15_rgb_mobilenet_4k.rst b/docs/source/samples/15_rgb_mobilenet_4k.rst index 77a1e770f..58f54f710 100644 --- a/docs/source/samples/15_rgb_mobilenet_4k.rst +++ b/docs/source/samples/15_rgb_mobilenet_4k.rst @@ -11,7 +11,7 @@ Demo .. raw:: html
- +
diff --git a/docs/source/samples/17_video_mobilenet.rst b/docs/source/samples/17_video_mobilenet.rst index 1d1f97b37..6f26cf86a 100644 --- a/docs/source/samples/17_video_mobilenet.rst +++ b/docs/source/samples/17_video_mobilenet.rst @@ -12,7 +12,7 @@ Demo .. raw:: html
- +
diff --git a/docs/source/samples/18_rgb_encoding_mobilenet.rst b/docs/source/samples/18_rgb_encoding_mobilenet.rst index 95ca4c0d3..664709cf3 100644 --- a/docs/source/samples/18_rgb_encoding_mobilenet.rst +++ b/docs/source/samples/18_rgb_encoding_mobilenet.rst @@ -18,7 +18,7 @@ Demo .. raw:: html
- +
Setup diff --git a/docs/source/samples/22_1_tiny_yolo_v3_decoding_on_device.rst b/docs/source/samples/22_1_tiny_yolo_v3_decoding_on_device.rst index c478fbf84..9213874bc 100644 --- a/docs/source/samples/22_1_tiny_yolo_v3_decoding_on_device.rst +++ b/docs/source/samples/22_1_tiny_yolo_v3_decoding_on_device.rst @@ -15,6 +15,12 @@ setConfidenceThreshold - confidence threshold above which objects are detected Demo #### +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/22_2_tiny_yolo_v4_decoding_on_device.rst b/docs/source/samples/22_2_tiny_yolo_v4_decoding_on_device.rst index b39859ae2..9770a8603 100644 --- a/docs/source/samples/22_2_tiny_yolo_v4_decoding_on_device.rst +++ b/docs/source/samples/22_2_tiny_yolo_v4_decoding_on_device.rst @@ -15,6 +15,12 @@ setConfidenceThreshold - confidence threshold above which objects are detected Demo #### +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/24_opencv_support.rst b/docs/source/samples/24_opencv_support.rst index bb69cf556..8f9e6bb5e 100644 --- a/docs/source/samples/24_opencv_support.rst +++ b/docs/source/samples/24_opencv_support.rst @@ -5,6 +5,15 @@ This example shows API which exposes both numpy and OpenCV compatible image type It uses ColorCamera node to retrieve both BGR interleaved 'preview' and NV12 encoded 'video' frames. Both are displayed using functions `getFrame` and `getCvFrame`. +Demo +#### + +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/25_system_information.rst b/docs/source/samples/25_system_information.rst index 65b21b81a..c9148776b 100644 --- a/docs/source/samples/25_system_information.rst +++ b/docs/source/samples/25_system_information.rst @@ -3,6 +3,43 @@ This example shows how to get system information (memory usage, cpu usage and temperature) from the board. +Demo +#### + +Example script output + +.. code-block:: + + Drr used / total - 0.13 / 414.80 MiB + Cmx used / total - 2.24 / 2.50 MiB + LeonCss heap used / total - 4.17 / 46.41 MiB + LeonMss heap used / total - 2.87 / 27.58 MiB + Chip temperature - average: 38.59, css: 39.81, mss: 37.71, upa0: 38.65, upa1: 38.18 + Cpu usage - Leon OS: 7.08%, Leon RT: 1.48 % + ---------------------------------------- + Drr used / total - 0.13 / 414.80 MiB + Cmx used / total - 2.24 / 2.50 MiB + LeonCss heap used / total - 4.17 / 46.41 MiB + LeonMss heap used / total - 2.87 / 27.58 MiB + Chip temperature - average: 38.59, css: 39.58, mss: 37.94, upa0: 38.18, upa1: 38.65 + Cpu usage - Leon OS: 1.55%, Leon RT: 0.30 % + ---------------------------------------- + Drr used / total - 0.13 / 414.80 MiB + Cmx used / total - 2.24 / 2.50 MiB + LeonCss heap used / total - 4.17 / 46.41 MiB + LeonMss heap used / total - 2.87 / 27.58 MiB + Chip temperature - average: 38.94, css: 40.04, mss: 38.18, upa0: 39.35, upa1: 38.18 + Cpu usage - Leon OS: 0.56%, Leon RT: 0.06 % + ---------------------------------------- + Drr used / total - 0.13 / 414.80 MiB + Cmx used / total - 2.24 / 2.50 MiB + LeonCss heap used / total - 4.17 / 46.41 MiB + LeonMss heap used / total - 2.87 / 27.58 MiB + Chip temperature - average: 39.46, css: 40.28, mss: 38.88, upa0: 39.81, upa1: 38.88 + Cpu usage - Leon OS: 0.51%, Leon RT: 0.06 % + ---------------------------------------- + + Setup ##### diff --git a/docs/source/samples/26_1_spatial_mobilenet.rst b/docs/source/samples/26_1_spatial_mobilenet.rst index 5677538b3..ad30e408b 100644 --- a/docs/source/samples/26_1_spatial_mobilenet.rst +++ b/docs/source/samples/26_1_spatial_mobilenet.rst @@ -11,6 +11,12 @@ setConfidenceThreshold - confidence threshold above which objects are detected Demo #### +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/26_2_spatial_mobilenet_mono.rst b/docs/source/samples/26_2_spatial_mobilenet_mono.rst index ac519d2e2..4a23a82b5 100644 --- a/docs/source/samples/26_2_spatial_mobilenet_mono.rst +++ b/docs/source/samples/26_2_spatial_mobilenet_mono.rst @@ -1,4 +1,4 @@ -26.2 - MONO & MobilenetSSD with spatial data +26.2 - Mono & MobilenetSSD with spatial data ============================================ This example shows how to run MobileNetv2SSD on the rectified right input frame, and @@ -11,6 +11,12 @@ setConfidenceThreshold - confidence threshold above which objects are detected Demo #### +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/26_3_spatial_tiny_yolo.rst b/docs/source/samples/26_3_spatial_tiny_yolo.rst index 29c13ba3b..46fe103b4 100644 --- a/docs/source/samples/26_3_spatial_tiny_yolo.rst +++ b/docs/source/samples/26_3_spatial_tiny_yolo.rst @@ -17,6 +17,12 @@ setConfidenceThreshold - confidence threshold above which objects are detected Demo #### +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/28_camera_video_example.rst b/docs/source/samples/28_camera_video_example.rst index 5288f0dbf..b3f6340e2 100644 --- a/docs/source/samples/28_camera_video_example.rst +++ b/docs/source/samples/28_camera_video_example.rst @@ -4,6 +4,15 @@ This example shows how to use high resolution video at low latency. Compared to :ref:`01 - RGB Preview`, this demo outputs NV12 frames whereas preview frames are BGR and are not suited for larger resoulution (eg. 2000x1000). Preview is more suitable for either NN or visualization purposes. +Demo +#### + +.. raw:: html + +
+ +
+ Setup ##### diff --git a/docs/source/samples/29_1_object_tracker.rst b/docs/source/samples/29_1_object_tracker.rst new file mode 100644 index 000000000..00443c765 --- /dev/null +++ b/docs/source/samples/29_1_object_tracker.rst @@ -0,0 +1,28 @@ +29.1 - Object tracker on RGB camera +=================================== + +This example shows how to run MobileNetv2SSD on the RGB input frame, and perform object tracking on persons. + +Demo +#### + + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + + +This example also requires MobilenetSDD blob (:code:`mobilenet.blob` file) to work - you can download it from +`here `__ + +Source code +########### + +Also `available on GitHub `__ + +.. literalinclude:: ../../../examples/29_1_object_tracker.py + :language: python + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/samples/29_2_spatial_object_tracker.rst b/docs/source/samples/29_2_spatial_object_tracker.rst new file mode 100644 index 000000000..a6897e289 --- /dev/null +++ b/docs/source/samples/29_2_spatial_object_tracker.rst @@ -0,0 +1,28 @@ +29.2 - Spatial object tracker on RGB camera +=========================================== + +This example shows how to run MobileNetv2SSD on the RGB input frame, and perform spatial object tracking on persons. + +Demo +#### + + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + + +This example also requires MobilenetSDD blob (:code:`mobilenet.blob` file) to work - you can download it from +`here `__ + +Source code +########### + +Also `available on GitHub `__ + +.. literalinclude:: ../../../examples/29_2_spatial_object_tracker.py + :language: python + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/samples/29_3_object_tracker_video.rst b/docs/source/samples/29_3_object_tracker_video.rst new file mode 100644 index 000000000..2df0b1993 --- /dev/null +++ b/docs/source/samples/29_3_object_tracker_video.rst @@ -0,0 +1,28 @@ +29.3 - Object tracker on video +============================== + +This example shows how to run MobileNetv2SSD on video input frame, and perform object tracking on persons. + +Demo +#### + + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + + +This example also requires MobilenetSDD based person-detection blob (:code:`person-detection-0201_openvino_2021.3_7shave.blob` file) to work - you can download it from +`here `__ + +Source code +########### + +Also `available on GitHub `__ + +.. literalinclude:: ../../../examples/29_3_object_tracker_video.py + :language: python + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/docs/source/samples/30_stereo_depth_from_host.rst b/docs/source/samples/30_stereo_depth_from_host.rst new file mode 100644 index 000000000..9a866a5ff --- /dev/null +++ b/docs/source/samples/30_stereo_depth_from_host.rst @@ -0,0 +1,24 @@ +30 - Stereo Depth from host +=========================== + +This example shows depth map from host using stereo images. There are 3 depth modes which you can select inside the code: left-right check, extended (for closer distance), subpixel (for longer distance). Otherwise a median with kernel_7x7 is activated. + +Setup +##### + +.. include:: /includes/install_from_pypi.rst + +This example also requires dataset folder - you can download it from +`here `__ + + +Source code +########### + +Also `available on GitHub `__ + +.. literalinclude:: ../../../examples/30_stereo_depth_from_host.py + :language: python + :linenos: + +.. include:: /includes/footer-short.rst diff --git a/examples/12_rgb_encoding_mono_mobilenet_depth.py b/examples/12_rgb_encoding_mono_mobilenet_depth.py index 7acac8099..eb7109272 100755 --- a/examples/12_rgb_encoding_mono_mobilenet_depth.py +++ b/examples/12_rgb_encoding_mono_mobilenet_depth.py @@ -37,7 +37,7 @@ camRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) depth = pipeline.createStereoDepth() -depth.setConfidenceThreshold(200) +depth.setConfidenceThreshold(255) # Note: the rectified streams are horizontally mirrored by default depth.setOutputRectified(True) depth.setRectifyEdgeFillColor(0) # Black, to better see the cutout @@ -83,11 +83,11 @@ # Start pipeline device.startPipeline() - queue_size = 8 - qRight = device.getOutputQueue("right", queue_size) - qDepth = device.getOutputQueue("depth", queue_size) - qManip = device.getOutputQueue("manip", queue_size) - qDet = device.getOutputQueue("nn", queue_size) + queueSize = 8 + qRight = device.getOutputQueue("right", queueSize) + qDepth = device.getOutputQueue("depth", queueSize) + qManip = device.getOutputQueue("manip", queueSize) + qDet = device.getOutputQueue("nn", queueSize) qRgbEnc = device.getOutputQueue('h265', maxSize=30, blocking=True) frame = None diff --git a/examples/14_color_camera_control.py b/examples/14_1_color_camera_control.py similarity index 100% rename from examples/14_color_camera_control.py rename to examples/14_1_color_camera_control.py diff --git a/examples/14_2_mono_camera_control.py b/examples/14_2_mono_camera_control.py new file mode 100755 index 000000000..659d94d55 --- /dev/null +++ b/examples/14_2_mono_camera_control.py @@ -0,0 +1,155 @@ +#!/usr/bin/env python3 + +""" +This example shows usage of mono camera in crop mode with the possibility to move the crop. +Uses 'WASD' controls to move the crop window, 'T' to trigger autofocus, 'IOKL,.' for manual exposure/focus: + Control: key[dec/inc] min..max + exposure time: I O 1..33000 [us] + sensitivity iso: K L 100..1600 +To go back to auto controls: + 'E' - autoexposure +""" + + +import cv2 +import depthai as dai + +# Step size ('W','A','S','D' controls) +stepSize = 0.02 +# Manual exposure/focus set step +expStep = 500 # us +isoStep = 50 + +# Start defining a pipeline +pipeline = dai.Pipeline() + +# Define a source - two mono (grayscale) camera +camRight = pipeline.createMonoCamera() +camRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) +camRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) +camLeft = pipeline.createMonoCamera() +camLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) +camLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) + +# Crop range +topLeft = dai.Point2f(0.4, 0.4) +bottomRight = dai.Point2f(0.6, 0.6) + +manipRight = pipeline.createImageManip() +manipRight.initialConfig.setCropRect(topLeft.x, topLeft.y, bottomRight.x, bottomRight.y) +manipLeft = pipeline.createImageManip() +manipLeft.initialConfig.setCropRect(topLeft.x, topLeft.y, bottomRight.x, bottomRight.y) +manipRight.setMaxOutputFrameSize(camRight.getResolutionHeight()*camRight.getResolutionWidth()*3) + +# Camera movement config (wasd) +configIn = pipeline.createXLinkIn() +configIn.setStreamName('config') +configIn.out.link(manipRight.inputConfig) +configIn.out.link(manipLeft.inputConfig) + +# Camera control (exp, iso, focus) +controlIn = pipeline.createXLinkIn() +controlIn.setStreamName('control') +controlIn.out.link(camRight.inputControl) +controlIn.out.link(camLeft.inputControl) + +# Linking with USB +camRight.out.link(manipRight.inputImage) +camLeft.out.link(manipLeft.inputImage) + +# Create outputs +manipOutRight = pipeline.createXLinkOut() +manipOutRight.setStreamName("right") +manipRight.out.link(manipOutRight.input) + +manipOutLeft = pipeline.createXLinkOut() +manipOutLeft.setStreamName("left") +manipLeft.out.link(manipOutLeft.input) + +def clamp(num, v0, v1): + return max(v0, min(num, v1)) + +# Pipeline defined, now the device is connected to +with dai.Device(pipeline) as device: + # Start pipeline + device.startPipeline() + + # Output queues will be used to get the grayscale frames + qRight = device.getOutputQueue(manipOutRight.getStreamName(), maxSize=4, blocking=False) + qLeft = device.getOutputQueue(manipOutLeft.getStreamName(), maxSize=4, blocking=False) + configQueue = device.getInputQueue(configIn.getStreamName()) + controlQueue = device.getInputQueue(controlIn.getStreamName()) + + def displayFrame(name, frame): + cv2.imshow(name, frame) + + sendCamConfig = False + + # Defaults and limits for manual focus/exposure controls + expTime = 20000 + expMin = 1 + expMax = 33000 + + sensIso = 800 + sensMin = 100 + sensMax = 1600 + + while True: + inRight = qRight.get() + inLeft = qLeft.get() + frameRight = inRight.getCvFrame() + frameLeft = inLeft.getCvFrame() + displayFrame("right", frameRight) + displayFrame("left", frameLeft) + + # Update screen + key = cv2.waitKey(1) + if key == ord('q'): + break + elif key == ord('c'): + ctrl = dai.CameraControl() + ctrl.setCaptureStill(True) + controlQueue.send(ctrl) + elif key == ord('e'): + print("Autoexposure enable") + ctrl = dai.CameraControl() + ctrl.setAutoExposureEnable() + controlQueue.send(ctrl) + elif key in [ord('i'), ord('o'), ord('k'), ord('l')]: + if key == ord('i'): expTime -= expStep + if key == ord('o'): expTime += expStep + if key == ord('k'): sensIso -= isoStep + if key == ord('l'): sensIso += isoStep + expTime = clamp(expTime, expMin, expMax) + sensIso = clamp(sensIso, sensMin, sensMax) + print("Setting manual exposure, time:", expTime, "iso:", sensIso) + ctrl = dai.CameraControl() + ctrl.setManualExposure(expTime, sensIso) + controlQueue.send(ctrl) + elif key == ord('w'): + if topLeft.y - stepSize >= 0: + topLeft.y -= stepSize + bottomRight.y -= stepSize + sendCamConfig = True + elif key == ord('a'): + if topLeft.x - stepSize >= 0: + topLeft.x -= stepSize + bottomRight.x -= stepSize + sendCamConfig = True + elif key == ord('s'): + if bottomRight.y + stepSize <= 1: + topLeft.y += stepSize + bottomRight.y += stepSize + sendCamConfig = True + elif key == ord('d'): + if bottomRight.x + stepSize <= 1: + topLeft.x += stepSize + bottomRight.x += stepSize + sendCamConfig = True + + + if sendCamConfig: + cfg = dai.ImageManipConfig() + cfg.setCropRect(topLeft.x, topLeft.y, bottomRight.x, bottomRight.y) + configQueue.send(cfg) + sendCamConfig = False diff --git a/examples/14_3_depth_crop_control.py b/examples/14_3_depth_crop_control.py new file mode 100755 index 000000000..87c25761f --- /dev/null +++ b/examples/14_3_depth_crop_control.py @@ -0,0 +1,108 @@ +#!/usr/bin/env python3 + +""" +This example shows usage of depth camera in crop mode with the possibility to move the crop. +Use 'WASD' in order to do it. +""" + +import cv2 +import depthai as dai +import numpy as np + +stepSize = 0.02 + +# Start defining a pipeline +pipeline = dai.Pipeline() + +# Define a source - two mono (grayscale) cameras +left = pipeline.createMonoCamera() +left.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +left.setBoardSocket(dai.CameraBoardSocket.LEFT) + +right = pipeline.createMonoCamera() +right.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +right.setBoardSocket(dai.CameraBoardSocket.RIGHT) + +# Crop range +topLeft = dai.Point2f(0.4, 0.4) +bottomRight = dai.Point2f(0.6, 0.6) + +manip = pipeline.createImageManip() +manip.initialConfig.setCropRect(topLeft.x, topLeft.y, bottomRight.x, bottomRight.y) +manip.setMaxOutputFrameSize(right.getResolutionHeight()*right.getResolutionWidth()*3) + + +# Create a node that will produce the depth map +stereo = pipeline.createStereoDepth() +stereo.setConfidenceThreshold(200) +stereo.setOutputDepth(True) + +left.out.link(stereo.left) +right.out.link(stereo.right) + + +# Control movement +controlIn = pipeline.createXLinkIn() +controlIn.setStreamName('control') +controlIn.out.link(manip.inputConfig) + +# Create outputs +xout = pipeline.createXLinkOut() +xout.setStreamName("depth") +stereo.depth.link(manip.inputImage) +manip.out.link(xout.input) + +# Pipeline defined, now the device is connected to +with dai.Device(pipeline) as device: + # Start pipeline + device.startPipeline() + + # Output queue will be used to get the depth frames from the outputs defined above + q = device.getOutputQueue(xout.getStreamName(), maxSize=4, blocking=False) + + sendCamConfig = False + + while True: + inDepth = q.get() # blocking call, will wait until a new data has arrived + # data is originally represented as a flat 1D array, it needs to be converted into HxW form + depthFrame = inDepth.getFrame() + # frame is transformed, the color map will be applied to highlight the depth info + depthFrameColor = cv2.normalize(depthFrame, None, 255, 0, cv2.NORM_INF, cv2.CV_8UC1) + depthFrameColor = cv2.equalizeHist(depthFrameColor) + depthFrameColor = cv2.applyColorMap(depthFrameColor, cv2.COLORMAP_HOT) + controlQueue = device.getInputQueue(controlIn.getStreamName()) + + # frame is ready to be shown + cv2.imshow("depth", depthFrameColor) + + # Update screen + key = cv2.waitKey(1) + if key == ord('q'): + break + elif key == ord('w'): + if topLeft.y - stepSize >= 0: + topLeft.y -= stepSize + bottomRight.y -= stepSize + sendCamConfig = True + elif key == ord('a'): + if topLeft.x - stepSize >= 0: + topLeft.x -= stepSize + bottomRight.x -= stepSize + sendCamConfig = True + elif key == ord('s'): + if bottomRight.y + stepSize <= 1: + topLeft.y += stepSize + bottomRight.y += stepSize + sendCamConfig = True + elif key == ord('d'): + if bottomRight.x + stepSize <= 1: + topLeft.x += stepSize + bottomRight.x += stepSize + sendCamConfig = True + + + if sendCamConfig: + cfg = dai.ImageManipConfig() + cfg.setCropRect(topLeft.x, topLeft.y, bottomRight.x, bottomRight.y) + controlQueue.send(cfg) + sendCamConfig = False \ No newline at end of file diff --git a/examples/26_1_spatial_mobilenet.py b/examples/26_1_spatial_mobilenet.py index ea268ca21..563a8b81e 100755 --- a/examples/26_1_spatial_mobilenet.py +++ b/examples/26_1_spatial_mobilenet.py @@ -75,7 +75,7 @@ monoRight.out.link(stereo.right) colorCam.preview.link(spatialDetectionNetwork.input) -if(syncNN): +if syncNN: spatialDetectionNetwork.passthrough.link(xoutRgb.input) else: colorCam.preview.link(xoutRgb.input) diff --git a/examples/26_2_spatial_mobilenet_mono.py b/examples/26_2_spatial_mobilenet_mono.py index 6c5148c86..7f5d50c3e 100755 --- a/examples/26_2_spatial_mobilenet_mono.py +++ b/examples/26_2_spatial_mobilenet_mono.py @@ -54,7 +54,7 @@ # Create outputs xoutManip = pipeline.createXLinkOut() xoutManip.setStreamName("right") -if(syncNN): +if syncNN: spatialDetectionNetwork.passthrough.link(xoutManip.input) else: manip.out.link(xoutManip.input) diff --git a/examples/26_3_spatial_tiny_yolo.py b/examples/26_3_spatial_tiny_yolo.py index fec9d179d..179aadd33 100755 --- a/examples/26_3_spatial_tiny_yolo.py +++ b/examples/26_3_spatial_tiny_yolo.py @@ -94,7 +94,7 @@ monoRight.out.link(stereo.right) colorCam.preview.link(spatialDetectionNetwork.input) -if(syncNN): +if syncNN: spatialDetectionNetwork.passthrough.link(xoutRgb.input) else: colorCam.preview.link(xoutRgb.input) diff --git a/examples/29_1_object_tracker.py b/examples/29_1_object_tracker.py new file mode 100755 index 000000000..27fe103ae --- /dev/null +++ b/examples/29_1_object_tracker.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 + +from pathlib import Path +import cv2 +import depthai as dai +import numpy as np +import time +import argparse + +labelMap = ["background", "aeroplane", "bicycle", "bird", "boat", "bottle", "bus", "car", "cat", "chair", "cow", + "diningtable", "dog", "horse", "motorbike", "person", "pottedplant", "sheep", "sofa", "train", "tvmonitor"] + +nnPathDefault = str((Path(__file__).parent / Path('models/mobilenet-ssd_openvino_2021.2_6shave.blob')).resolve().absolute()) +parser = argparse.ArgumentParser() +parser.add_argument('nnPath', nargs='?', help="Path to mobilenet detection network blob", default=nnPathDefault) +parser.add_argument('-ff', '--full_frame', action="store_true", help="Perform tracking on full RGB frame", default=False) + +args = parser.parse_args() + + +fullFrameTracking = args.full_frame + +# Start defining a pipeline +pipeline = dai.Pipeline() + +colorCam = pipeline.createColorCamera() +detectionNetwork = pipeline.createMobileNetDetectionNetwork() +objectTracker = pipeline.createObjectTracker() +trackerOut = pipeline.createXLinkOut() + +xlinkOut = pipeline.createXLinkOut() + +xlinkOut.setStreamName("preview") +trackerOut.setStreamName("tracklets") + +colorCam.setPreviewSize(300, 300) +colorCam.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P) +colorCam.setInterleaved(False) +colorCam.setColorOrder(dai.ColorCameraProperties.ColorOrder.BGR) +colorCam.setFps(40) + +# setting node configs +detectionNetwork.setBlobPath(args.nnPath) +detectionNetwork.setConfidenceThreshold(0.5) +detectionNetwork.input.setBlocking(False) + +# Link plugins CAM . NN . XLINK +colorCam.preview.link(detectionNetwork.input) +objectTracker.passthroughTrackerFrame.link(xlinkOut.input) + + +objectTracker.setDetectionLabelsToTrack([15]) # track only person +# possible tracking types: ZERO_TERM_COLOR_HISTOGRAM, ZERO_TERM_IMAGELESS +objectTracker.setTrackerType(dai.TrackerType.ZERO_TERM_COLOR_HISTOGRAM) +# take the smallest ID when new object is tracked, possible options: SMALLEST_ID, UNIQUE_ID +objectTracker.setTrackerIdAssigmentPolicy(dai.TrackerIdAssigmentPolicy.SMALLEST_ID) + +if fullFrameTracking: + colorCam.video.link(objectTracker.inputTrackerFrame) +else: + detectionNetwork.passthrough.link(objectTracker.inputTrackerFrame) + +detectionNetwork.passthrough.link(objectTracker.inputDetectionFrame) +detectionNetwork.out.link(objectTracker.inputDetections) +objectTracker.out.link(trackerOut.input) + + +# Pipeline defined, now the device is connected to +with dai.Device(pipeline) as device: + + # Start the pipeline + device.startPipeline() + + preview = device.getOutputQueue("preview", 4, False) + tracklets = device.getOutputQueue("tracklets", 4, False) + + startTime = time.monotonic() + counter = 0 + fps = 0 + frame = None + + while(True): + imgFrame = preview.get() + track = tracklets.get() + + counter+=1 + current_time = time.monotonic() + if (current_time - startTime) > 1 : + fps = counter / (current_time - startTime) + counter = 0 + startTime = current_time + + color = (255, 0, 0) + frame = imgFrame.getCvFrame() + trackletsData = track.tracklets + for t in trackletsData: + roi = t.roi.denormalize(frame.shape[1], frame.shape[0]) + x1 = int(roi.topLeft().x) + y1 = int(roi.topLeft().y) + x2 = int(roi.bottomRight().x) + y2 = int(roi.bottomRight().y) + + try: + label = labelMap[t.label] + except: + label = t.label + + statusMap = {dai.Tracklet.TrackingStatus.NEW : "NEW", dai.Tracklet.TrackingStatus.TRACKED : "TRACKED", dai.Tracklet.TrackingStatus.LOST : "LOST"} + cv2.putText(frame, str(label), (x1 + 10, y1 + 20), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(frame, f"ID: {[t.id]}", (x1 + 10, y1 + 35), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(frame, statusMap[t.status], (x1 + 10, y1 + 50), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.rectangle(frame, (x1, y1), (x2, y2), color, cv2.FONT_HERSHEY_SIMPLEX) + + cv2.putText(frame, "NN fps: {:.2f}".format(fps), (2, frame.shape[0] - 4), cv2.FONT_HERSHEY_TRIPLEX, 0.4, color) + + cv2.imshow("tracker", frame) + + if cv2.waitKey(1) == ord('q'): + break diff --git a/examples/29_2_spatial_object_tracker.py b/examples/29_2_spatial_object_tracker.py new file mode 100755 index 000000000..e0c15a962 --- /dev/null +++ b/examples/29_2_spatial_object_tracker.py @@ -0,0 +1,146 @@ +#!/usr/bin/env python3 + +from pathlib import Path +import cv2 +import depthai as dai +import numpy as np +import time +import argparse + +labelMap = ["background", "aeroplane", "bicycle", "bird", "boat", "bottle", "bus", "car", "cat", "chair", "cow", + "diningtable", "dog", "horse", "motorbike", "person", "pottedplant", "sheep", "sofa", "train", "tvmonitor"] + +nnPathDefault = str((Path(__file__).parent / Path('models/mobilenet-ssd_openvino_2021.2_6shave.blob')).resolve().absolute()) +parser = argparse.ArgumentParser() +parser.add_argument('nnPath', nargs='?', help="Path to mobilenet detection network blob", default=nnPathDefault) +parser.add_argument('-ff', '--full_frame', action="store_true", help="Perform tracking on full RGB frame", default=False) + +args = parser.parse_args() + + +fullFrameTracking = args.full_frame + +# Start defining a pipeline +pipeline = dai.Pipeline() + +colorCam = pipeline.createColorCamera() +spatialDetectionNetwork = pipeline.createMobileNetSpatialDetectionNetwork() +monoLeft = pipeline.createMonoCamera() +monoRight = pipeline.createMonoCamera() +stereo = pipeline.createStereoDepth() +objectTracker = pipeline.createObjectTracker() + +xoutRgb = pipeline.createXLinkOut() +trackerOut = pipeline.createXLinkOut() + +xoutRgb.setStreamName("preview") +trackerOut.setStreamName("tracklets") + +colorCam.setPreviewSize(300, 300) +colorCam.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P) +colorCam.setInterleaved(False) +colorCam.setColorOrder(dai.ColorCameraProperties.ColorOrder.BGR) + +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) + +# setting node configs +stereo.setOutputDepth(True) +stereo.setConfidenceThreshold(255) + +spatialDetectionNetwork.setBlobPath(args.nnPath) +spatialDetectionNetwork.setConfidenceThreshold(0.5) +spatialDetectionNetwork.input.setBlocking(False) +spatialDetectionNetwork.setBoundingBoxScaleFactor(0.5) +spatialDetectionNetwork.setDepthLowerThreshold(100) +spatialDetectionNetwork.setDepthUpperThreshold(5000) + +# Create outputs + +monoLeft.out.link(stereo.left) +monoRight.out.link(stereo.right) + +# Link plugins CAM . NN . XLINK +colorCam.preview.link(spatialDetectionNetwork.input) +objectTracker.passthroughTrackerFrame.link(xoutRgb.input) + + +objectTracker.setDetectionLabelsToTrack([15]) # track only person +# possible tracking types: ZERO_TERM_COLOR_HISTOGRAM, ZERO_TERM_IMAGELESS +objectTracker.setTrackerType(dai.TrackerType.ZERO_TERM_COLOR_HISTOGRAM) +# take the smallest ID when new object is tracked, possible options: SMALLEST_ID, UNIQUE_ID +objectTracker.setTrackerIdAssigmentPolicy(dai.TrackerIdAssigmentPolicy.SMALLEST_ID) + +objectTracker.out.link(trackerOut.input) +if fullFrameTracking: + colorCam.setPreviewKeepAspectRatio(False) + colorCam.video.link(objectTracker.inputTrackerFrame) + objectTracker.inputTrackerFrame.setBlocking(False) + # do not block the pipeline if it's too slow on full frame + objectTracker.inputTrackerFrame.setQueueSize(2) +else: + spatialDetectionNetwork.passthrough.link(objectTracker.inputTrackerFrame) + +spatialDetectionNetwork.passthrough.link(objectTracker.inputDetectionFrame) +spatialDetectionNetwork.out.link(objectTracker.inputDetections) + +stereo.depth.link(spatialDetectionNetwork.inputDepth) + + +# Pipeline defined, now the device is connected to +with dai.Device(pipeline) as device: + + # Start the pipeline + device.startPipeline() + + preview = device.getOutputQueue("preview", 4, False) + tracklets = device.getOutputQueue("tracklets", 4, False) + + startTime = time.monotonic() + counter = 0 + fps = 0 + frame = None + + while(True): + imgFrame = preview.get() + track = tracklets.get() + + counter+=1 + current_time = time.monotonic() + if (current_time - startTime) > 1 : + fps = counter / (current_time - startTime) + counter = 0 + startTime = current_time + + color = (255, 0, 0) + frame = imgFrame.getCvFrame() + trackletsData = track.tracklets + for t in trackletsData: + roi = t.roi.denormalize(frame.shape[1], frame.shape[0]) + x1 = int(roi.topLeft().x) + y1 = int(roi.topLeft().y) + x2 = int(roi.bottomRight().x) + y2 = int(roi.bottomRight().y) + + try: + label = labelMap[t.label] + except: + label = t.label + statusMap = {dai.Tracklet.TrackingStatus.NEW : "NEW", dai.Tracklet.TrackingStatus.TRACKED : "TRACKED", dai.Tracklet.TrackingStatus.LOST : "LOST"} + cv2.putText(frame, str(label), (x1 + 10, y1 + 20), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(frame, f"ID: {[t.id]}", (x1 + 10, y1 + 35), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(frame, statusMap[t.status], (x1 + 10, y1 + 50), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.rectangle(frame, (x1, y1), (x2, y2), color, cv2.FONT_HERSHEY_SIMPLEX) + + cv2.putText(frame, f"X: {int(t.spatialCoordinates.x)} mm", (x1 + 10, y1 + 65), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(frame, f"Y: {int(t.spatialCoordinates.y)} mm", (x1 + 10, y1 + 80), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(frame, f"Z: {int(t.spatialCoordinates.z)} mm", (x1 + 10, y1 + 95), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + + cv2.putText(frame, "NN fps: {:.2f}".format(fps), (2, frame.shape[0] - 4), cv2.FONT_HERSHEY_TRIPLEX, 0.4, color) + + cv2.imshow("tracker", frame) + + if cv2.waitKey(1) == ord('q'): + break diff --git a/examples/29_3_object_tracker_video.py b/examples/29_3_object_tracker_video.py new file mode 100755 index 000000000..7f0a5fced --- /dev/null +++ b/examples/29_3_object_tracker_video.py @@ -0,0 +1,180 @@ +#!/usr/bin/env python3 + +from pathlib import Path +import cv2 +import depthai as dai +import numpy as np +import time +import argparse + +labelMap = ["person", ""] + +nnPathDefault = str((Path(__file__).parent / Path('models/person-detection-0201_openvino_2021.3_7shave.blob')).resolve().absolute()) +videoPathDefault = str((Path(__file__).parent / Path('models/construction_vest.mp4')).resolve().absolute()) +parser = argparse.ArgumentParser() +parser.add_argument('-nnPath', help="Path to mobilenet detection network blob", default=nnPathDefault) +parser.add_argument('-v', '--videoPath', help="Path to video frame", default=videoPathDefault) + +args = parser.parse_args() + +# Start defining a pipeline +pipeline = dai.Pipeline() + +# Create neural network input +xinFrame = pipeline.createXLinkIn() +xinFrame.setStreamName("inFrame") +xinFrame.setMaxDataSize(1920*1080*3) + +detectionNetwork = pipeline.createMobileNetDetectionNetwork() +objectTracker = pipeline.createObjectTracker() +trackerOut = pipeline.createXLinkOut() + +xlinkOut = pipeline.createXLinkOut() + +xlinkOut.setStreamName("trackerFrame") +trackerOut.setStreamName("tracklets") + +# Create a node to convert the grayscale frame into the nn-acceptable form +manip = pipeline.createImageManip() +manip.initialConfig.setResizeThumbnail(384, 384) +# manip.initialConfig.setResize(384, 384) +# manip.initialConfig.setKeepAspectRatio(False) #squash the image to not lose FOV +# The NN model expects BGR input. By default ImageManip output type would be same as input (gray in this case) +manip.initialConfig.setFrameType(dai.RawImgFrame.Type.BGR888p) +xinFrame.out.link(manip.inputImage) +manip.inputImage.setBlocking(True) + +manipOut = pipeline.createXLinkOut() +manipOut.setStreamName("manip") +manip.out.link(manipOut.input) + +nnOut = pipeline.createXLinkOut() +nnOut.setStreamName("nn") +detectionNetwork.out.link(nnOut.input) + + +# setting node configs +detectionNetwork.setBlobPath(args.nnPath) +detectionNetwork.setConfidenceThreshold(0.5) + +manip.out.link(detectionNetwork.input) +detectionNetwork.input.setBlocking(True) +objectTracker.passthroughTrackerFrame.link(xlinkOut.input) + + +objectTracker.setDetectionLabelsToTrack([0]) # track only person +# possible tracking types: ZERO_TERM_COLOR_HISTOGRAM, ZERO_TERM_IMAGELESS +objectTracker.setTrackerType(dai.TrackerType.ZERO_TERM_COLOR_HISTOGRAM) +# take the smallest ID when new object is tracked, possible options: SMALLEST_ID, UNIQUE_ID +objectTracker.setTrackerIdAssigmentPolicy(dai.TrackerIdAssigmentPolicy.SMALLEST_ID) + +xinFrame.out.link(objectTracker.inputTrackerFrame) +objectTracker.inputTrackerFrame.setBlocking(True) +detectionNetwork.passthrough.link(objectTracker.inputDetectionFrame) +objectTracker.inputDetectionFrame.setBlocking(True) +detectionNetwork.out.link(objectTracker.inputDetections) +objectTracker.inputDetections.setBlocking(True) +objectTracker.out.link(trackerOut.input) + + +# Pipeline defined, now the device is connected to +with dai.Device(pipeline) as device: + + # Start the pipeline + device.startPipeline() + + qIn = device.getInputQueue(name="inFrame") + trackerFrameQ = device.getOutputQueue("trackerFrame", 4) + tracklets = device.getOutputQueue("tracklets", 4) + qManip = device.getOutputQueue("manip", maxSize=4) + qDet = device.getOutputQueue("nn", maxSize=4) + + startTime = time.monotonic() + counter = 0 + fps = 0 + detections = [] + frame = None + + def to_planar(arr: np.ndarray, shape: tuple) -> np.ndarray: + return cv2.resize(arr, shape).transpose(2, 0, 1).flatten() + + # nn data, being the bounding box locations, are in <0..1> range - they need to be normalized with frame width/height + def frameNorm(frame, bbox): + normVals = np.full(len(bbox), frame.shape[0]) + normVals[::2] = frame.shape[1] + return (np.clip(np.array(bbox), 0, 1) * normVals).astype(int) + + def displayFrame(name, frame): + for detection in detections: + bbox = frameNorm(frame, (detection.xmin, detection.ymin, detection.xmax, detection.ymax)) + cv2.rectangle(frame, (bbox[0], bbox[1]), (bbox[2], bbox[3]), (255, 0, 0), 2) + cv2.putText(frame, labelMap[detection.label], (bbox[0] + 10, bbox[1] + 20), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255) + cv2.putText(frame, f"{int(detection.confidence * 100)}%", (bbox[0] + 10, bbox[1] + 40), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255) + cv2.imshow(name, frame) + + cap = cv2.VideoCapture(args.videoPath) + baseTs = time.monotonic() + simulatedFps = 30 + inputFrameShape = (1280, 720) + + while cap.isOpened(): + read_correctly, frame = cap.read() + if not read_correctly: + break + + img = dai.ImgFrame() + img.setType(dai.RawImgFrame.Type.BGR888p) + img.setData(to_planar(frame, inputFrameShape)) + img.setTimestamp(baseTs) + baseTs += 1/simulatedFps + + img.setWidth(inputFrameShape[0]) + img.setHeight(inputFrameShape[1]) + qIn.send(img) + + trackFrame = trackerFrameQ.tryGet() + if trackFrame is None: + continue + + track = tracklets.get() + manip = qManip.get() + inDet = qDet.get() + + counter+=1 + current_time = time.monotonic() + if (current_time - startTime) > 1 : + fps = counter / (current_time - startTime) + counter = 0 + startTime = current_time + + detections = inDet.detections + manipFrame = manip.getCvFrame() + displayFrame("nn", manipFrame) + + color = (255, 0, 0) + trackerFrame = trackFrame.getCvFrame() + trackletsData = track.tracklets + for t in trackletsData: + roi = t.roi.denormalize(trackerFrame.shape[1], trackerFrame.shape[0]) + x1 = int(roi.topLeft().x) + y1 = int(roi.topLeft().y) + x2 = int(roi.bottomRight().x) + y2 = int(roi.bottomRight().y) + + try: + label = labelMap[t.label] + except: + label = t.label + + statusMap = {dai.Tracklet.TrackingStatus.NEW : "NEW", dai.Tracklet.TrackingStatus.TRACKED : "TRACKED", dai.Tracklet.TrackingStatus.LOST : "LOST"} + cv2.putText(trackerFrame, str(label), (x1 + 10, y1 + 20), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(trackerFrame, f"ID: {[t.id]}", (x1 + 10, y1 + 35), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.putText(trackerFrame, statusMap[t.status], (x1 + 10, y1 + 50), cv2.FONT_HERSHEY_TRIPLEX, 0.5, color) + cv2.rectangle(trackerFrame, (x1, y1), (x2, y2), color, cv2.FONT_HERSHEY_SIMPLEX) + + cv2.putText(trackerFrame, "Fps: {:.2f}".format(fps), (2, trackerFrame.shape[0] - 4), cv2.FONT_HERSHEY_TRIPLEX, 0.4, color) + + cv2.imshow("tracker", trackerFrame) + + if cv2.waitKey(1) == ord('q'): + break diff --git a/examples/30_stereo_depth_from_host.py b/examples/30_stereo_depth_from_host.py new file mode 100755 index 000000000..bdd6af3da --- /dev/null +++ b/examples/30_stereo_depth_from_host.py @@ -0,0 +1,188 @@ +#!/usr/bin/env python3 + +import cv2 +import numpy as np +import depthai as dai +from time import sleep +import datetime +import argparse +from pathlib import Path + +datasetDefault = str((Path(__file__).parent / Path('models/dataset')).resolve().absolute()) +parser = argparse.ArgumentParser() +parser.add_argument('-dataset', nargs='?', help="Path to recorded frames", default=datasetDefault) +args = parser.parse_args() + +if not Path(datasetDefault).exists(): + import sys + raise FileNotFoundError(f'Required file/s not found, please run "{sys.executable} install_requirements.py"') + + +# StereoDepth config options. +out_depth = False # Disparity by default +out_rectified = True # Output and display rectified streams +lrcheck = True # Better handling for occlusions +extended = False # Closer-in minimum depth, disparity range is doubled +subpixel = True # Better accuracy for longer distance, fractional disparity 32-levels +median = dai.StereoDepthProperties.MedianFilter.KERNEL_7x7 + +# Sanitize some incompatible options +if lrcheck or extended or subpixel: + median = dai.StereoDepthProperties.MedianFilter.MEDIAN_OFF + +print("StereoDepth config options: ") +print("Left-Right check: ", lrcheck) +print("Extended disparity: ", extended) +print("Subpixel: ", subpixel) +print("Median filtering: ", median) + +right_intrinsic = [[860.0, 0.0, 640.0], [0.0, 860.0, 360.0], [0.0, 0.0, 1.0]] + + +def create_stereo_depth_pipeline(): + print("Creating Stereo Depth pipeline: ", end='') + + print("XLINK IN -> STEREO -> XLINK OUT") + pipeline = dai.Pipeline() + + camLeft = pipeline.createXLinkIn() + camRight = pipeline.createXLinkIn() + stereo = pipeline.createStereoDepth() + xoutLeft = pipeline.createXLinkOut() + xoutRight = pipeline.createXLinkOut() + xoutDepth = pipeline.createXLinkOut() + xoutDisparity = pipeline.createXLinkOut() + xoutRectifLeft = pipeline.createXLinkOut() + xoutRectifRight = pipeline.createXLinkOut() + + camLeft.setStreamName('in_left') + camRight.setStreamName('in_right') + + stereo.setOutputDepth(out_depth) + stereo.setOutputRectified(out_rectified) + stereo.setConfidenceThreshold(200) + stereo.setRectifyEdgeFillColor(0) # Black, to better see the cutout + stereo.setMedianFilter(median) # KERNEL_7x7 default + stereo.setLeftRightCheck(lrcheck) + stereo.setExtendedDisparity(extended) + stereo.setSubpixel(subpixel) + + stereo.setEmptyCalibration() # Set if the input frames are already rectified + stereo.setInputResolution(1280, 720) + + xoutLeft.setStreamName('left') + xoutRight.setStreamName('right') + xoutDepth.setStreamName('depth') + xoutDisparity.setStreamName('disparity') + xoutRectifLeft.setStreamName('rectified_left') + xoutRectifRight.setStreamName('rectified_right') + + camLeft.out.link(stereo.left) + camRight.out.link(stereo.right) + stereo.syncedLeft.link(xoutLeft.input) + stereo.syncedRight.link(xoutRight.input) + stereo.depth.link(xoutDepth.input) + stereo.disparity.link(xoutDisparity.input) + stereo.rectifiedLeft.link(xoutRectifLeft.input) + stereo.rectifiedRight.link(xoutRectifRight.input) + + streams = ['left', 'right'] + if out_rectified: + streams.extend(['rectified_left', 'rectified_right']) + streams.extend(['disparity', 'depth']) + + return pipeline, streams + + +def convert_to_cv2_frame(name, image): + baseline = 75 #mm + focal = right_intrinsic[0][0] + max_disp = 96 + disp_type = np.uint8 + disp_levels = 1 + if (extended): + max_disp *= 2 + if (subpixel): + max_disp *= 32 + disp_type = np.uint16 + disp_levels = 32 + + data, w, h = image.getData(), image.getWidth(), image.getHeight() + if name == 'depth': + # this contains FP16 with (lrcheck or extended or subpixel) + frame = np.array(data).astype(np.uint8).view(np.uint16).reshape((h, w)) + elif name == 'disparity': + disp = np.array(data).astype(np.uint8).view(disp_type).reshape((h, w)) + + # Compute depth from disparity + with np.errstate(divide='ignore'): + depth = (disp_levels * baseline * focal / disp).astype(np.uint16) + + if 1: # Optionally, extend disparity range to better visualize it + frame = (disp * 255. / max_disp).astype(np.uint8) + + if 1: # Optionally, apply a color map + frame = cv2.applyColorMap(frame, cv2.COLORMAP_HOT) + + else: # mono streams / single channel + frame = np.array(data).reshape((h, w)).astype(np.uint8) + if name.startswith('rectified_'): + frame = cv2.flip(frame, 1) + if name == 'rectified_right': + last_rectif_right = frame + return frame + + +pipeline, streams = create_stereo_depth_pipeline() + +print("Creating DepthAI device") +with dai.Device(pipeline) as device: + print("Starting pipeline") + device.startPipeline() + + inStreams = ['in_right', 'in_left'] + inStreamsCameraID = [dai.CameraBoardSocket.RIGHT, dai.CameraBoardSocket.LEFT] + in_q_list = [] + for s in inStreams: + q = device.getInputQueue(s) + in_q_list.append(q) + + # Create a receive queue for each stream + q_list = [] + for s in streams: + q = device.getOutputQueue(s, 8, blocking=False) + q_list.append(q) + + # Need to set a timestamp for input frames, for the sync stage in Stereo node + timestamp_ms = 0 + index = 0 + while True: + # Handle input streams, if any + if in_q_list: + dataset_size = 2 # Number of image pairs + frame_interval_ms = 500 + for i, q in enumerate(in_q_list): + path = args.dataset + '/' + str(index) + '/' + q.getName() + '.png' + data = cv2.imread(path, cv2.IMREAD_GRAYSCALE).reshape(720*1280) + tstamp = datetime.timedelta(seconds = timestamp_ms // 1000, + milliseconds = timestamp_ms % 1000) + img = dai.ImgFrame() + img.setData(data) + img.setTimestamp(tstamp) + img.setInstanceNum(inStreamsCameraID[i]) + img.setWidth(1280) + img.setHeight(720) + q.send(img) + if timestamp_ms == 0: # Send twice for first iteration + q.send(img) + print("Sent frame: {:25s}".format(path), 'timestamp_ms:', timestamp_ms) + timestamp_ms += frame_interval_ms + index = (index + 1) % dataset_size + sleep(frame_interval_ms / 1000) + # Handle output streams + for q in q_list: + if q.getName() in ['left', 'right', 'depth']: continue + frame = convert_to_cv2_frame(q.getName(), q.get()) + cv2.imshow(q.getName(), frame) + if cv2.waitKey(1) == ord('q'): + break diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index f9753f6b4..b504319d1 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -12,7 +12,8 @@ if(UNIX) set(SYS_PATH_SEPARATOR ":") endif() -add_custom_target(install_requirements +# Add a target to install_requirements (added to ALL) +add_custom_target(install_requirements ALL COMMAND ${PYTHON_EXECUTABLE} "${CMAKE_CURRENT_LIST_DIR}/install_requirements.py" "--skip_depthai" DEPENDS ${TARGET_NAME} VERBATIM @@ -70,7 +71,7 @@ if(DEPTHAI_PYTHON_TEST_EXAMPLES) "PYTHONPATH=$${SYS_PATH_SEPARATOR}$ENV{PYTHONPATH}" # ASAN in case of sanitizers ${ASAN_ENVIRONMENT_VARS} - ${CMAKE_COMMAND} -DTIMEOUT_SECONDS=300 -P ${CMAKE_CURRENT_LIST_DIR}/cmake/ExecuteTestTimeout.cmake + ${CMAKE_COMMAND} -DFORCE_TIMEOUT_SECONDS=300 -P ${CMAKE_CURRENT_LIST_DIR}/cmake/ExecuteTestTimeout.cmake # Actual script to run ${PYTHON_EXECUTABLE} "${CMAKE_CURRENT_LIST_DIR}/install_requirements.py" "--skip_depthai" ) @@ -94,7 +95,9 @@ add_python_example(10_mono_depth_mobilenetssd 10_mono_depth_mobilenetssd.py) add_python_example(11_rgb_encoding_mono_mobilenet 11_rgb_encoding_mono_mobilenet.py) add_python_example(12_rgb_encoding_mono_mobilenet_depth 12_rgb_encoding_mono_mobilenet_depth.py) add_python_example(13_encoding_max_limit 13_encoding_max_limit.py) -add_python_example(14_color_camera_control 14_color_camera_control.py) +add_python_example(14_1_color_camera_control 14_1_color_camera_control.py) +add_python_example(14_2_mono_camera_control 14_2_mono_camera_control.py) +add_python_example(14_3_depth_crop_control 14_3_depth_crop_control.py) add_python_example(15_rgb_mobilenet_4k 15_rgb_mobilenet_4k.py) add_python_example(16_device_queue_event 16_device_queue_event.py) add_python_example(17_video_mobilenet 17_video_mobilenet.py) @@ -113,3 +116,7 @@ add_python_example(26_3_spatial_tiny_yolo_v3 26_3_spatial_tiny_yolo.py) add_python_example(26_3_spatial_tiny_yolo_v4 26_3_spatial_tiny_yolo.py) add_python_example(27_spatial_location_calculator 27_spatial_location_calculator.py) add_python_example(28_camera_video_example 28_camera_video_example.py) +add_python_example(29_1_object_tracker 29_1_object_tracker.py) +add_python_example(29_2_spatial_object_tracker 29_2_spatial_object_tracker.py) +add_python_example(29_3_object_tracker_video 29_3_object_tracker_video.py) +add_python_example(30_stereo_depth_from_host 30_stereo_depth_from_host.py) diff --git a/examples/README.md b/examples/README.md index ab5d2164c..aaed656c2 100644 --- a/examples/README.md +++ b/examples/README.md @@ -57,28 +57,65 @@ TEST_TIMEOUT=0 ctest -R "01_rgb_preview" --verbose ![example_7](https://user-images.githubusercontent.com/5244214/104040905-86209480-51d8-11eb-9e15-5fe94aba7b69.gif) ### 08_rgb_mobilenet.py -![example_8](https://user-images.githubusercontent.com/5244214/112524084-b58a7a80-8d9f-11eb-9389-e17b0ea40338.gif) +![example_8](https://user-images.githubusercontent.com/5244214/112838840-cb4cb800-909d-11eb-8264-83d3c1e5f348.gif) ### 09_mono_mobilenet.py -![example_9](https://user-images.githubusercontent.com/5244214/104040898-8456d100-51d8-11eb-9498-e316b71d41e6.gif) +![example_9](https://user-images.githubusercontent.com/5244214/112838832-ca1b8b00-909d-11eb-8ea1-eafeb98c3266.gif) ### 10_mono_depth_mobilenetssd.py **NOTE** For clearness, a `disparity` output is used instead of `depth`, as disparity is better to visualize -![example_10](https://user-images.githubusercontent.com/5244214/104056108-35b53100-51f0-11eb-9677-63e5fb5bcb83.gif) +![example_10](https://user-images.githubusercontent.com/5244214/112838828-c8ea5e00-909d-11eb-912a-ce3995a68bfd.gif) ### 11_rgb_encoding_mono_mobilenet.py -![example_11](https://user-images.githubusercontent.com/5244214/104740909-cb007a00-5748-11eb-8250-c07ee6bf980a.gif) +![example_11](https://user-images.githubusercontent.com/5244214/112838821-c851c780-909d-11eb-86d4-d7a6b6d0aebe.gif) ### 12_rgb_encoding_mono_mobilenet_depth.py **NOTE** For clearness, a `disparity` output is used instead of `depth`, as disparity is better to visualize -![example_12](https://user-images.githubusercontent.com/5244214/104741001-e9667580-5748-11eb-92d3-39dd726b0992.gif) +![example_12](https://user-images.githubusercontent.com/5244214/112838818-c7209a80-909d-11eb-8f50-81c023c59e9b.gif) ### 13_encoding_max_limit.py ![example_13](https://user-images.githubusercontent.com/5244214/104741072-0307bd00-5749-11eb-97f3-9422c8b0d8da.gif) ### 14_color_camera_control.py ![example_14](https://user-images.githubusercontent.com/5244214/104741150-187ce700-5749-11eb-8bd5-3d4f37d2d22a.gif) + +### 15_rgb_mobilenet_4k.py +![15](https://user-images.githubusercontent.com/5244214/112838812-c556d700-909d-11eb-8194-83602530c9af.gif) + +### 16_device_queue_event.py +![16](https://user-images.githubusercontent.com/5244214/112838810-c425aa00-909d-11eb-9962-550533f13268.gif) + +### 17_video_mobilenet.py +![17](https://user-images.githubusercontent.com/5244214/112838807-c38d1380-909d-11eb-9c89-878eaa20e4ed.gif) + +### 18_rgb_encoding_mobilenet.py +![18](https://user-images.githubusercontent.com/5244214/112838805-c25be680-909d-11eb-8db2-2d0ce61aebe0.gif) + +### 22_1_tiny_yolo_v3_device_side_decoding.py +![22_1](https://user-images.githubusercontent.com/5244214/112838798-c12ab980-909d-11eb-8e6c-5aa3d623c7e9.gif) + +### 22_2_tiny_yolo_v4_device_side_decoding.py +![22_2](https://user-images.githubusercontent.com/5244214/112838790-bff98c80-909d-11eb-8b85-7c4dbd9a0e62.gif) + +### 23_autoexposure_roi.py +![23](https://user-images.githubusercontent.com/5244214/112838784-be2fc900-909d-11eb-8067-291636ae9950.gif) + +### 24_opencv_support.py +![24](https://user-images.githubusercontent.com/5244214/112838789-bf60f600-909d-11eb-9fb5-203dbec774f8.gif) + +### 26_1_spatial_mobilenet.py +![26_1](https://user-images.githubusercontent.com/5244214/112838781-bcfe9c00-909d-11eb-9d12-a9834f545271.gif) + +### 26_2_spatial_mobilenet_mono.py +![26_2](https://user-images.githubusercontent.com/5244214/112838777-bbcd6f00-909d-11eb-9b1e-d93159c3d88f.gif) + +### 26_3_spatial_tiny_yolo.py +![26_3](https://user-images.githubusercontent.com/5244214/112838772-ba9c4200-909d-11eb-9678-0703df46b529.gif) + +### 28_camera_video_example.py +![28](https://user-images.githubusercontent.com/5244214/112838767-b8d27e80-909d-11eb-92f0-5af20c4326b7.gif) + diff --git a/examples/cmake/ExecuteTestTimeout.cmake b/examples/cmake/ExecuteTestTimeout.cmake index 781b4d7d2..5a0236a0f 100644 --- a/examples/cmake/ExecuteTestTimeout.cmake +++ b/examples/cmake/ExecuteTestTimeout.cmake @@ -16,11 +16,17 @@ list(REMOVE_AT arguments 0) message(STATUS "arguments: ${arguments}") # Check if ENV variable TEST_TIMEOUT is set and use that rather than TIMEOUT_SECONDS -if(DEFINED ENV{TEST_TIMEOUT}) +if(DEFINED ENV{TEST_TIMEOUT} AND NOT DEFINED FORCE_TIMEOUT_SECONDS) message(STATUS "Overriding timeout: ${TIMEOUT_SECONDS} with $ENV{TEST_TIMEOUT}") set(TIMEOUT_SECONDS $ENV{TEST_TIMEOUT}) endif() +# Check if FORCE_TIMEOUT_SECONDS is set, in that case respect that option +if(FORCE_TIMEOUT_SECONDS) + message(STATUS "Forcing timeout of ${FORCE_TIMEOUT_SECONDS} seconds") + set(TIMEOUT_SECONDS ${FORCE_TIMEOUT_SECONDS}) +endif() + # Execute the example (SIGTERM for now, could be improved with SIGINT -> SIGKILL) if(TIMEOUT_SECONDS GREATER 0) execute_process(COMMAND ${arguments} TIMEOUT ${TIMEOUT_SECONDS} RESULT_VARIABLE error_variable) diff --git a/examples/models/.gitignore b/examples/models/.gitignore index 2d85c3ce1..2df6dc094 100644 --- a/examples/models/.gitignore +++ b/examples/models/.gitignore @@ -1,2 +1,3 @@ *.blob -*.mp4 \ No newline at end of file +*.mp4 +dataset/ diff --git a/examples/models/person-detection-0201/model.yml b/examples/models/person-detection-0201/model.yml new file mode 100644 index 000000000..1201b13c1 --- /dev/null +++ b/examples/models/person-detection-0201/model.yml @@ -0,0 +1,25 @@ +# Copyright (c) 2021 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +description: >- + person-detection-0201 +task_type: object_attributes +files: + - name: person-detection-0201_openvino_2021.3_7shave.blob + size: 8362880 + sha256: c61e856bf2a733c18df039f10e1b24d317536051db846093aa644347c4d55c48 + source: https://artifacts.luxonis.com/artifactory/luxonis-depthai-data-local/network/person-detection-0201_openvino_2021.3_7shave.blob + +framework: dldt +license: https://raw.githubusercontent.com/openvinotoolkit/open_model_zoo/master/LICENSE diff --git a/examples/models/stereo-dataset/model.yml b/examples/models/stereo-dataset/model.yml new file mode 100644 index 000000000..65b98e1d7 --- /dev/null +++ b/examples/models/stereo-dataset/model.yml @@ -0,0 +1,31 @@ +# Copyright (c) 2021 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +description: >- + stereo dataset to test frames sent from host +task_type: object_attributes +files: + - name: dataset.zip + size: 2361554 + sha256: 19abe0e4126fc32ea45441abaaf5bed39603493530f616f416531c1c2fe05b86 + source: + $type: google_drive + id: 1mPyghc_0odGtSU2cROS1uLD-qwRU8aug +postprocessing: + - $type: unpack_archive + format: zip + file: dataset.zip + +framework: dldt +license: https://vision.middlebury.edu/stereo/data/scenes2014/ diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 4ddc8cef7..055f57a59 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -15,6 +15,7 @@ #include "depthai/pipeline/datatype/SystemInformation.hpp" #include "depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp" #include "depthai/pipeline/datatype/SpatialLocationCalculatorConfig.hpp" +#include "depthai/pipeline/datatype/Tracklets.hpp" // depthai-shared #include "depthai-shared/datatype/RawBuffer.hpp" @@ -28,6 +29,7 @@ #include "depthai-shared/datatype/RawSpatialLocationCalculatorConfig.hpp" #include "depthai-shared/datatype/RawSpatialLocations.hpp" #include "depthai-shared/datatype/RawSpatialLocationCalculatorConfig.hpp" +#include "depthai-shared/datatype/RawTracklets.hpp" //pybind @@ -259,6 +261,29 @@ 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) + .def_readwrite("id", &Tracklet::id) + .def_readwrite("label", &Tracklet::label) + .def_readwrite("status", &Tracklet::status) + .def_readwrite("srcImgDetection", &Tracklet::srcImgDetection) + .def_readwrite("spatialCoordinates", &Tracklet::spatialCoordinates) + ; + + py::enum_(tracklet, "TrackingStatus") + .value("NEW", Tracklet::TrackingStatus::NEW) + .value("TRACKED", Tracklet::TrackingStatus::TRACKED) + .value("LOST", Tracklet::TrackingStatus::LOST) + ; + + // Bind RawTracklets + py::class_> rawTacklets(m, "RawTracklets", DOC(dai, RawTracklets)); + rawTacklets + .def_readwrite("tracklets", &RawTracklets::tracklets) + ; + // RawCameraControl enum bindings // The enum fields will also be exposed in 'CameraControl', store them for later std::vector camCtrlAttr; @@ -772,4 +797,11 @@ void DatatypeBindings::bind(pybind11::module& m){ .def("getConfigData", &SpatialLocationCalculatorConfig::getConfigData, DOC(dai, SpatialLocationCalculatorConfig, getConfigData)) ; + // Tracklets (after ConfigData) + py::class_>(m, "Tracklets", DOC(dai, Tracklets)) + .def(py::init<>()) + .def_property("tracklets", [](Tracklets& track) { return &track.tracklets; }, [](Tracklets& track, std::vector val) { track.tracklets = val; }, DOC(dai, Tracklets, tracklets)) + ; + + } \ No newline at end of file diff --git a/src/openvino/OpenVINOBindings.cpp b/src/openvino/OpenVINOBindings.cpp index f5d33df30..6ad3346ac 100644 --- a/src/openvino/OpenVINOBindings.cpp +++ b/src/openvino/OpenVINOBindings.cpp @@ -31,6 +31,7 @@ void OpenVINOBindings::bind(pybind11::module& m){ .value("VERSION_2020_4", OpenVINO::Version::VERSION_2020_4) .value("VERSION_2021_1", OpenVINO::Version::VERSION_2021_1) .value("VERSION_2021_2", OpenVINO::Version::VERSION_2021_2) + .value("VERSION_2021_3", OpenVINO::Version::VERSION_2021_3) .export_values() ; diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index 20be95cf1..168c7e310 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -14,6 +14,7 @@ #include "depthai/pipeline/node/SystemLogger.hpp" #include "depthai/pipeline/node/SpatialLocationCalculator.hpp" #include "depthai/pipeline/node/SpatialDetectionNetwork.hpp" +#include "depthai/pipeline/node/ObjectTracker.hpp" // Libraries #include "hedley/hedley.h" @@ -26,7 +27,7 @@ void NodeBindings::bind(pybind11::module& m){ // Base 'Node' class binding py::class_> pyNode(m, "Node", DOC(dai, Node)); - pyNode + pyNode .def_readonly("id", &Node::id, DOC(dai, Node, id)) .def("getName", &Node::getName, DOC(dai, Node, getName)) .def("getOutputs", &Node::getOutputs, DOC(dai, Node, getOutputs)) @@ -58,7 +59,7 @@ void NodeBindings::bind(pybind11::module& m){ .def_property("inputId", [](Node::Connection& conn) { return conn.inputId; }, [](Node::Connection& conn, Node::Id id) {conn.inputId = id; }, DOC(dai, Node, Connection, inputId)) .def_property("inputName", [](Node::Connection& conn) { return conn.inputName; }, [](Node::Connection& conn, std::string name) {conn.inputName = name; }, DOC(dai, Node, Connection, inputName)) ; - // MSVC errors out with: + // MSVC errors out with: // Error C2326 'void NodeBindings::bind(pybind11::module &)': function cannot access 'dai::Node::Connection::outputId' // ... // py::class_(pyNode, "Connection") @@ -75,10 +76,10 @@ void NodeBindings::bind(pybind11::module& m){ .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)) - .def("setNumFrames", &XLinkIn::setNumFrames, py::arg("numFrames"), DOC(dai, node, XLinkIn, setNumFrames)) + .def("setNumFrames", &XLinkIn::setNumFrames, py::arg("numFrames"), DOC(dai, node, XLinkIn, setNumFrames)) .def("getStreamName", &XLinkIn::getStreamName, DOC(dai, node, XLinkIn, getStreamName)) .def("getMaxDataSize", &XLinkIn::getMaxDataSize, DOC(dai, node, XLinkIn, getMaxDataSize)) - .def("getNumFrames", &XLinkIn::getNumFrames, DOC(dai, node, XLinkIn, getNumFrames)) + .def("getNumFrames", &XLinkIn::getNumFrames, DOC(dai, node, XLinkIn, getNumFrames)) ; // XLinkOut node @@ -113,7 +114,7 @@ void NodeBindings::bind(pybind11::module& m){ PyErr_WarnEx(PyExc_DeprecationWarning, "getCamId() is deprecated, use getBoardSocket() instead.", 1); HEDLEY_DIAGNOSTIC_PUSH HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED - return c.getCamId(); + return c.getCamId(); HEDLEY_DIAGNOSTIC_POP }) .def("setBoardSocket", &ColorCamera::setBoardSocket, py::arg("boardSocket"), DOC(dai, node, ColorCamera, setBoardSocket)) @@ -155,7 +156,7 @@ void NodeBindings::bind(pybind11::module& m){ .def("setPreviewKeepAspectRatio", &ColorCamera::setPreviewKeepAspectRatio, py::arg("keep"), DOC(dai, node, ColorCamera, setPreviewKeepAspectRatio)) .def("getPreviewKeepAspectRatio", &ColorCamera::getPreviewKeepAspectRatio, DOC(dai, node, ColorCamera, getPreviewKeepAspectRatio)) ; - + // NeuralNetwork node @@ -178,7 +179,7 @@ void NodeBindings::bind(pybind11::module& m){ .def_readonly("out", &ImageManip::out, DOC(dai, node, ImageManip, out)) .def_readonly("initialConfig", &ImageManip::initialConfig, DOC(dai, node, ImageManip, initialConfig)) // setters - + .def("setCropRect", [](ImageManip& im, float xmin, float ymin, float xmax, float ymax) { // Issue a deprecation warning PyErr_WarnEx(PyExc_DeprecationWarning, "setCropRect() is deprecated, use initialConfig.setCropRect() instead.", 1); @@ -231,7 +232,7 @@ void NodeBindings::bind(pybind11::module& m){ im.setHorizontalFlip(flip); HEDLEY_DIAGNOSTIC_POP }) - + .def("setKeepAspectRatio", &ImageManip::setKeepAspectRatio, DOC(dai, node, ImageManip, setKeepAspectRatio)) .def("setWaitForConfigInput", &ImageManip::setWaitForConfigInput, DOC(dai, node, ImageManip, setWaitForConfigInput)) @@ -272,7 +273,7 @@ void NodeBindings::bind(pybind11::module& m){ .def("getResolutionWidth", &MonoCamera::getResolutionWidth, DOC(dai, node, MonoCamera, getResolutionWidth)) .def("getResolutionHeight", &MonoCamera::getResolutionHeight, DOC(dai, node, MonoCamera, getResolutionHeight)) ; - + // StereoDepth node @@ -303,19 +304,21 @@ void NodeBindings::bind(pybind11::module& m){ // VideoEncoder node py::class_>(m, "VideoEncoder", DOC(dai, node, VideoEncoder)) .def_readonly("input", &VideoEncoder::input, DOC(dai, node, VideoEncoder, input), DOC(dai, node, VideoEncoder, input)) - .def_readonly("bitstream", &VideoEncoder::bitstream, DOC(dai, node, VideoEncoder, bitstream), DOC(dai, node, VideoEncoder, bitstream)) + .def_readonly("bitstream", &VideoEncoder::bitstream, DOC(dai, node, VideoEncoder, bitstream), DOC(dai, node, VideoEncoder, bitstream)) .def("setDefaultProfilePreset", (void(VideoEncoder::*)(int, int, float, VideoEncoderProperties::Profile))&VideoEncoder::setDefaultProfilePreset, py::arg("width"), py::arg("height"), py::arg("fps"), py::arg("profile"), DOC(dai, node, VideoEncoder, setDefaultProfilePreset)) .def("setDefaultProfilePreset", (void(VideoEncoder::*)(std::tuple, float, VideoEncoderProperties::Profile))&VideoEncoder::setDefaultProfilePreset, py::arg("size"), py::arg("fps"), py::arg("profile"), DOC(dai, node, VideoEncoder, setDefaultProfilePreset, 2)) .def("setNumFramesPool", &VideoEncoder::setNumFramesPool, py::arg("frames"), DOC(dai, node, VideoEncoder, setNumFramesPool)) .def("getNumFramesPool", &VideoEncoder::getNumFramesPool, DOC(dai, node, VideoEncoder, getNumFramesPool)) .def("setRateControlMode", &VideoEncoder::setRateControlMode, py::arg("mode"), DOC(dai, node, VideoEncoder, setRateControlMode)) - .def("setProfile", &VideoEncoder::setProfile, py::arg("width"), py::arg("height"), py::arg("profile"), DOC(dai, node, VideoEncoder, setProfile)) + .def("setProfile", static_cast, VideoEncoder::Properties::Profile)>(&VideoEncoder::setProfile), py::arg("size"), py::arg("profile"), DOC(dai, node, VideoEncoder, setProfile)) + .def("setProfile", static_cast(&VideoEncoder::setProfile), py::arg("width"), py::arg("height"), py::arg("profile"), DOC(dai, node, VideoEncoder, setProfile, 2)) .def("setBitrate", &VideoEncoder::setBitrate, py::arg("bitrateKbps"), DOC(dai, node, VideoEncoder, setBitrate)) .def("setBitrateKbps", &VideoEncoder::setBitrateKbps, py::arg("bitrateKbps"), DOC(dai, node, VideoEncoder, setBitrateKbps)) .def("setKeyframeFrequency", &VideoEncoder::setKeyframeFrequency, py::arg("freq"), DOC(dai, node, VideoEncoder, setKeyframeFrequency)) //.def("setMaxBitrate", &VideoEncoder::setMaxBitrate) .def("setNumBFrames", &VideoEncoder::setNumBFrames, py::arg("numBFrames"), DOC(dai, node, VideoEncoder, setNumBFrames)) .def("setQuality", &VideoEncoder::setQuality, py::arg("quality"), DOC(dai, node, VideoEncoder, setQuality)) + .def("setLossless", &VideoEncoder::setLossless, DOC(dai, node, VideoEncoder, setLossless)) .def("setFrameRate", &VideoEncoder::setFrameRate, py::arg("frameRate"), DOC(dai, node, VideoEncoder, setFrameRate)) .def("getRateControlMode", &VideoEncoder::getRateControlMode, DOC(dai, node, VideoEncoder, getRateControlMode)) .def("getProfile", &VideoEncoder::getProfile, DOC(dai, node, VideoEncoder, getProfile)) @@ -329,6 +332,7 @@ void NodeBindings::bind(pybind11::module& m){ .def("getHeight", &VideoEncoder::getHeight, DOC(dai, node, VideoEncoder, getHeight)) .def("getFrameRate", &VideoEncoder::getFrameRate, DOC(dai, node, VideoEncoder, getFrameRate)) .def("getSize", &VideoEncoder::getSize, DOC(dai, node, VideoEncoder, getSize)) + .def("getLossless", &VideoEncoder::getLossless, DOC(dai, node, VideoEncoder, getLossless)) ; // SPIOut node @@ -385,7 +389,7 @@ void NodeBindings::bind(pybind11::module& m){ // SpatialLocationCalculator node py::class_>(m, "SpatialLocationCalculator", DOC(dai, node, SpatialLocationCalculator)) - .def_readonly("inputConfig", &SpatialLocationCalculator::inputConfig, DOC(dai, node, SpatialLocationCalculator, inputConfig)) + .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)) .def_readonly("passthroughDepth", &SpatialLocationCalculator::passthroughDepth, DOC(dai, node, SpatialLocationCalculator, passthroughDepth)) @@ -399,6 +403,22 @@ void NodeBindings::bind(pybind11::module& m){ .def("setRate", &SystemLogger::setRate, py::arg("hz"), DOC(dai, node, SystemLogger, setRate)) ; + // NeuralNetwork node + py::class_>(m, "ObjectTracker", DOC(dai, node, 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)) + .def_readonly("out", &ObjectTracker::out, DOC(dai, node, ObjectTracker, out)) + .def_readonly("passthroughTrackerFrame", &ObjectTracker::passthroughTrackerFrame, DOC(dai, node, ObjectTracker, passthroughTrackerFrame)) + .def_readonly("passthroughDetectionFrame", &ObjectTracker::passthroughDetectionFrame, DOC(dai, node, ObjectTracker, passthroughDetectionFrame)) + .def_readonly("passthroughDetections", &ObjectTracker::passthroughDetections, DOC(dai, node, ObjectTracker, passthroughDetections)) + + .def("setTrackerThreshold", &ObjectTracker::setTrackerThreshold, py::arg("threshold"), DOC(dai, node, ObjectTracker, setTrackerThreshold)) + .def("setMaxObjectsToTrack", &ObjectTracker::setMaxObjectsToTrack, py::arg("maxObjectsToTrack"), DOC(dai, node, ObjectTracker, setMaxObjectsToTrack)) + .def("setDetectionLabelsToTrack", &ObjectTracker::setDetectionLabelsToTrack, py::arg("labels"), DOC(dai, node, ObjectTracker, setDetectionLabelsToTrack)) + .def("setTrackerType", &ObjectTracker::setTrackerType, py::arg("type"), DOC(dai, node, ObjectTracker, setTrackerType)) + .def("setTrackerIdAssigmentPolicy", &ObjectTracker::setTrackerIdAssigmentPolicy, py::arg("type"), DOC(dai, node, ObjectTracker, setTrackerIdAssigmentPolicy)) + ; //////////////////////////////////// // Node properties bindings @@ -434,7 +454,7 @@ void NodeBindings::bind(pybind11::module& m){ // ALIAS m.attr("ColorCamera").attr("Properties") = colorCameraProperties; - + // MonoCamera props py::class_ monoCameraProperties(m, "MonoCameraProperties", DOC(dai, MonoCameraProperties)); @@ -452,7 +472,7 @@ void NodeBindings::bind(pybind11::module& m){ ; // ALIAS m.attr("MonoCamera").attr("Properties") = monoCameraProperties; - + // StereoDepth props py::class_ stereoDepthProperties(m, "StereoDepthProperties", DOC(dai, StereoDepthProperties)); @@ -479,7 +499,7 @@ void NodeBindings::bind(pybind11::module& m){ ; // ALIAS m.attr("StereoDepth").attr("Properties") = stereoDepthProperties; - + // VideoEncoder props @@ -508,7 +528,7 @@ void NodeBindings::bind(pybind11::module& m){ 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; @@ -561,4 +581,25 @@ void NodeBindings::bind(pybind11::module& m){ 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; + } diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index 9b1666f13..8d2f8ec09 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -17,6 +17,7 @@ #include "depthai/pipeline/node/SystemLogger.hpp" #include "depthai/pipeline/node/SpatialLocationCalculator.hpp" #include "depthai/pipeline/node/SpatialDetectionNetwork.hpp" +#include "depthai/pipeline/node/ObjectTracker.hpp" // depthai-shared #include "depthai-shared/properties/GlobalProperties.hpp" @@ -74,6 +75,7 @@ void PipelineBindings::bind(pybind11::module& m){ .def("createSpatialLocationCalculator", &Pipeline::create) .def("createMobileNetSpatialDetectionNetwork", &Pipeline::create) .def("createYoloSpatialDetectionNetwork", &Pipeline::create) + .def("createObjectTracker", &Pipeline::create) ;