| @@ -261,6 +261,22 @@ jobs: | |||
| - uses: actions/checkout@v3 | |||
| - uses: r7kamura/rust-problem-matchers@v1.1.0 | |||
| - run: cargo --version --verbose | |||
| - name: Free Disk Space (Ubuntu) | |||
| uses: jlumbroso/free-disk-space@main | |||
| if: runner.os == 'Linux' | |||
| with: | |||
| # this might remove tools that are actually needed, | |||
| # if set to "true" but frees about 6 GB | |||
| tool-cache: false | |||
| # all of these default to true, but feel free to set to | |||
| # "false" if necessary for your workflow | |||
| android: true | |||
| dotnet: true | |||
| haskell: true | |||
| large-packages: false | |||
| docker-images: true | |||
| swap-storage: false | |||
| - uses: Swatinem/rust-cache@v2 | |||
| with: | |||
| cache-provider: buildjet | |||
| @@ -315,14 +331,15 @@ jobs: | |||
| cd test_python_project | |||
| dora up | |||
| dora list | |||
| dora build dataflow.yml | |||
| dora start dataflow.yml --name ci-python-test --detach | |||
| sleep 10 | |||
| dora stop --name ci-python-test --grace-duration 5s | |||
| pip install "numpy<2.0.0" opencv-python | |||
| dora build ../examples/python-dataflow/dataflow_dynamic.yml | |||
| dora start ../examples/python-dataflow/dataflow_dynamic.yml --name ci-python-dynamic --detach | |||
| python ../examples/python-dataflow/plot_dynamic.py | |||
| opencv-plot --name plot | |||
| sleep 5 | |||
| dora stop --name ci-python-test --grace-duration 5s | |||
| dora stop --name ci-python-dynamic --grace-duration 5s | |||
| dora destroy | |||
| - name: "Test CLI (C)" | |||
| @@ -343,7 +360,7 @@ jobs: | |||
| sleep 10 | |||
| dora stop --name ci-c-test --grace-duration 5s | |||
| dora destroy | |||
| - name: "Test CLI (C++)" | |||
| timeout-minutes: 30 | |||
| # fail-fast by using bash shell explictly | |||
| @@ -30,8 +30,8 @@ members = [ | |||
| "libraries/shared-memory-server", | |||
| "libraries/extensions/download", | |||
| "libraries/extensions/telemetry/*", | |||
| "tool_nodes/dora-record", | |||
| "tool_nodes/dora-rerun", | |||
| "node-hub/dora-record", | |||
| "node-hub/dora-rerun", | |||
| "libraries/extensions/ros2-bridge", | |||
| "libraries/extensions/ros2-bridge/msg-gen", | |||
| "libraries/extensions/ros2-bridge/python", | |||
| @@ -1,25 +1,41 @@ | |||
| # Python Dataflow Example | |||
| This examples shows how to create and connect dora operators and custom nodes in Python. | |||
| This examples shows how to create and connect dora nodes in Python. | |||
| ## Overview | |||
| The [`dataflow.yml`](./dataflow.yml) defines a simple dataflow graph with the following three nodes: | |||
| - a webcam node, that connects to your webcam and feed the dataflow with webcam frame as jpeg compressed bytearray. | |||
| - an object detection node, that apply Yolo v5 on the webcam image. The model is imported from Pytorch Hub. The output is the bounding box of each object detected, the confidence and the class. You can have more info here: https://pytorch.org/hub/ultralytics_yolov5/ | |||
| - a window plotting node, that will retrieve the webcam image and the Yolov5 bounding box and join the two together. | |||
| - a window plotting node, that will retrieve the webcam image and plot it. | |||
| The same dataflow is implemented for a `dynamic-node` in [`dataflow_dynamic.yml`](./dataflow_dynamic.yml). It contains | |||
| the same nodes as the previous dataflow, but the plot node is a dynamic node. See the next section for more | |||
| information on how to start such a dataflow. | |||
| ## Getting started | |||
| After installing Rust, `dora-cli` and `Python >3.11`, you will need to **activate** (or create and **activate**) a | |||
| [Python virtual environment](https://docs.python.org/3/library/venv.html). | |||
| Then, you will need to install the dependencies: | |||
| ```bash | |||
| cargo run --example python-dataflow | |||
| cd examples/python-dataflow | |||
| dora build ./dataflow.yml (or dora build ./dataflow_dynamic.yml) | |||
| ``` | |||
| ## Run the dataflow as a standalone | |||
| It will install the required dependencies for the Python nodes. | |||
| - Start the `dora-daemon`: | |||
| Then you can run the dataflow: | |||
| ```bash | |||
| dora up | |||
| dora start ./dataflow.yml (or dora start ./dataflow_dynamic.yml) | |||
| ``` | |||
| ../../target/release/dora-daemon --run-dataflow dataflow.yml | |||
| ``` | |||
| **Note**: if you're running the dynamic dataflow, you will need to start manually the ultralytics-yolo node: | |||
| ```bash | |||
| # activate your virtual environment in another terminal | |||
| python opencv-plot --name plot | |||
| ``` | |||
| @@ -1,25 +1,33 @@ | |||
| nodes: | |||
| - id: webcam | |||
| custom: | |||
| source: ./webcam.py | |||
| inputs: | |||
| tick: | |||
| source: dora/timer/millis/50 | |||
| queue_size: 1000 | |||
| outputs: | |||
| - image | |||
| - id: camera | |||
| build: pip install ../../node-hub/opencv-video-capture | |||
| path: opencv-video-capture | |||
| inputs: | |||
| tick: dora/timer/millis/20 | |||
| outputs: | |||
| - image | |||
| env: | |||
| CAPTURE_PATH: 0 | |||
| IMAGE_WIDTH: 640 | |||
| IMAGE_HEIGHT: 480 | |||
| - id: object_detection | |||
| custom: | |||
| source: ./object_detection.py | |||
| inputs: | |||
| image: webcam/image | |||
| outputs: | |||
| - bbox | |||
| - id: object-detection | |||
| build: pip install ../../node-hub/ultralytics-yolo | |||
| path: ultralytics-yolo | |||
| inputs: | |||
| image: | |||
| source: camera/image | |||
| queue_size: 1 | |||
| outputs: | |||
| - bbox | |||
| env: | |||
| MODEL: yolov8n.pt | |||
| - id: plot | |||
| custom: | |||
| source: ./plot.py | |||
| inputs: | |||
| image: webcam/image | |||
| bbox: object_detection/bbox | |||
| build: pip install ../../node-hub/opencv-plot | |||
| path: opencv-plot | |||
| inputs: | |||
| image: | |||
| source: camera/image | |||
| queue_size: 1 | |||
| bbox: object-detection/bbox | |||
| @@ -1,16 +1,18 @@ | |||
| nodes: | |||
| - id: webcam | |||
| custom: | |||
| source: ./webcam.py | |||
| inputs: | |||
| tick: | |||
| source: dora/timer/millis/50 | |||
| queue_size: 1000 | |||
| outputs: | |||
| - image | |||
| - id: camera | |||
| build: pip install ../../node-hub/opencv-video-capture | |||
| path: opencv-video-capture | |||
| inputs: | |||
| tick: dora/timer/millis/16 | |||
| outputs: | |||
| - image | |||
| env: | |||
| CAPTURE_PATH: 0 | |||
| IMAGE_WIDTH: 640 | |||
| IMAGE_HEIGHT: 480 | |||
| - id: plot | |||
| custom: | |||
| source: dynamic | |||
| inputs: | |||
| image: webcam/image | |||
| build: pip install ../../node-hub/opencv-plot | |||
| path: dynamic | |||
| inputs: | |||
| image: camera/image | |||
| @@ -1,5 +0,0 @@ | |||
| from dora import Node | |||
| node = Node("plot") | |||
| event = node.next() | |||
| @@ -1,40 +0,0 @@ | |||
| #!/usr/bin/env python3 | |||
| # -*- coding: utf-8 -*- | |||
| import cv2 | |||
| import numpy as np | |||
| from ultralytics import YOLO | |||
| from dora import Node | |||
| import pyarrow as pa | |||
| model = YOLO("yolov8n.pt") | |||
| node = Node() | |||
| for event in node: | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| event_id = event["id"] | |||
| if event_id == "image": | |||
| print("[object detection] received image input") | |||
| frame = event["value"].to_numpy() | |||
| frame = cv2.imdecode(frame, -1) | |||
| frame = frame[:, :, ::-1] # OpenCV image (BGR to RGB) | |||
| results = model(frame) # includes NMS | |||
| # Process results | |||
| boxes = np.array(results[0].boxes.xyxy.cpu()) | |||
| conf = np.array(results[0].boxes.conf.cpu()) | |||
| label = np.array(results[0].boxes.cls.cpu()) | |||
| # concatenate them together | |||
| arrays = np.concatenate((boxes, conf[:, None], label[:, None]), axis=1) | |||
| node.send_output("bbox", pa.array(arrays.ravel()), event["metadata"]) | |||
| else: | |||
| print("[object detection] ignoring unexpected input:", event_id) | |||
| elif event_type == "STOP": | |||
| print("[object detection] received stop") | |||
| elif event_type == "ERROR": | |||
| print("[object detection] error: ", event["error"]) | |||
| else: | |||
| print("[object detection] received unexpected event:", event_type) | |||
| @@ -1,96 +0,0 @@ | |||
| #!/usr/bin/env python3 | |||
| # -*- coding: utf-8 -*- | |||
| import os | |||
| from dora import Node | |||
| from dora import DoraStatus | |||
| import cv2 | |||
| import numpy as np | |||
| from utils import LABELS | |||
| CI = os.environ.get("CI") | |||
| font = cv2.FONT_HERSHEY_SIMPLEX | |||
| class Plotter: | |||
| """ | |||
| Plot image and bounding box | |||
| """ | |||
| def __init__(self): | |||
| self.image = [] | |||
| self.bboxs = [] | |||
| def on_input( | |||
| self, | |||
| dora_input, | |||
| ) -> DoraStatus: | |||
| """ | |||
| Put image and bounding box on cv2 window. | |||
| Args: | |||
| dora_input["id"] (str): Id of the dora_input declared in the yaml configuration | |||
| dora_input["value"] (arrow array): message of the dora_input | |||
| """ | |||
| if dora_input["id"] == "image": | |||
| frame = dora_input["value"].to_numpy() | |||
| frame = cv2.imdecode(frame, -1) | |||
| self.image = frame | |||
| elif dora_input["id"] == "bbox" and len(self.image) != 0: | |||
| bboxs = dora_input["value"].to_numpy() | |||
| self.bboxs = np.reshape(bboxs, (-1, 6)) | |||
| for bbox in self.bboxs: | |||
| [ | |||
| min_x, | |||
| min_y, | |||
| max_x, | |||
| max_y, | |||
| confidence, | |||
| label, | |||
| ] = bbox | |||
| cv2.rectangle( | |||
| self.image, | |||
| (int(min_x), int(min_y)), | |||
| (int(max_x), int(max_y)), | |||
| (0, 255, 0), | |||
| 2, | |||
| ) | |||
| cv2.putText( | |||
| self.image, | |||
| LABELS[int(label)] + f", {confidence:0.2f}", | |||
| (int(max_x), int(max_y)), | |||
| font, | |||
| 0.75, | |||
| (0, 255, 0), | |||
| 2, | |||
| 1, | |||
| ) | |||
| if CI != "true": | |||
| cv2.imshow("frame", self.image) | |||
| if cv2.waitKey(1) & 0xFF == ord("q"): | |||
| return DoraStatus.STOP | |||
| return DoraStatus.CONTINUE | |||
| plotter = Plotter() | |||
| node = Node() | |||
| for event in node: | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| status = plotter.on_input(event) | |||
| if status == DoraStatus.CONTINUE: | |||
| pass | |||
| elif status == DoraStatus.STOP: | |||
| print("plotter returned stop status") | |||
| break | |||
| elif event_type == "STOP": | |||
| print("received stop") | |||
| else: | |||
| print("received unexpected event:", event_type) | |||
| @@ -1,97 +0,0 @@ | |||
| #!/usr/bin/env python3 | |||
| # -*- coding: utf-8 -*- | |||
| import os | |||
| from dora import Node | |||
| from dora import DoraStatus | |||
| import cv2 | |||
| import numpy as np | |||
| from utils import LABELS | |||
| CI = os.environ.get("CI") | |||
| font = cv2.FONT_HERSHEY_SIMPLEX | |||
| class Plotter: | |||
| """ | |||
| Plot image and bounding box | |||
| """ | |||
| def __init__(self): | |||
| self.image = [] | |||
| self.bboxs = [] | |||
| def on_input( | |||
| self, | |||
| dora_input, | |||
| ) -> DoraStatus: | |||
| """ | |||
| Put image and bounding box on cv2 window. | |||
| Args: | |||
| dora_input["id"] (str): Id of the dora_input declared in the yaml configuration | |||
| dora_input["value"] (arrow array): message of the dora_input | |||
| """ | |||
| if dora_input["id"] == "image": | |||
| frame = dora_input["value"].to_numpy() | |||
| frame = cv2.imdecode(frame, -1) | |||
| self.image = frame | |||
| elif dora_input["id"] == "bbox" and len(self.image) != 0: | |||
| bboxs = dora_input["value"].to_numpy() | |||
| self.bboxs = np.reshape(bboxs, (-1, 6)) | |||
| for bbox in self.bboxs: | |||
| [ | |||
| min_x, | |||
| min_y, | |||
| max_x, | |||
| max_y, | |||
| confidence, | |||
| label, | |||
| ] = bbox | |||
| cv2.rectangle( | |||
| self.image, | |||
| (int(min_x), int(min_y)), | |||
| (int(max_x), int(max_y)), | |||
| (0, 255, 0), | |||
| 2, | |||
| ) | |||
| cv2.putText( | |||
| self.image, | |||
| LABELS[int(label)] + f", {confidence:0.2f}", | |||
| (int(max_x), int(max_y)), | |||
| font, | |||
| 0.75, | |||
| (0, 255, 0), | |||
| 2, | |||
| 1, | |||
| ) | |||
| if CI != "true": | |||
| cv2.imshow("frame", self.image) | |||
| if cv2.waitKey(1) & 0xFF == ord("q"): | |||
| return DoraStatus.STOP | |||
| return DoraStatus.CONTINUE | |||
| plotter = Plotter() | |||
| node = Node("plot") | |||
| for event in node: | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| status = plotter.on_input(event) | |||
| if status == DoraStatus.CONTINUE: | |||
| pass | |||
| elif status == DoraStatus.STOP: | |||
| print("plotter returned stop status") | |||
| break | |||
| elif event_type == "STOP": | |||
| print("received stop") | |||
| else: | |||
| print("received unexpected event:", event_type) | |||
| @@ -1,47 +0,0 @@ | |||
| # YOLOv5 requirements | |||
| # Usage: pip install -r requirements.txt | |||
| # Base ---------------------------------------- | |||
| ultralytics | |||
| gitpython | |||
| ipython # interactive notebook | |||
| matplotlib>=3.2.2 | |||
| numpy<2.0.0 # See: https://github.com/opencv/opencv-python/issues/997 | |||
| opencv-python>=4.1.1 | |||
| Pillow>=7.1.2 | |||
| psutil # system resources | |||
| PyYAML>=5.3.1 | |||
| requests>=2.23.0 | |||
| scipy>=1.4.1 | |||
| thop>=0.1.1 # FLOPs computation | |||
| torch # see https://pytorch.org/get-started/locally (recommended) | |||
| torchvision | |||
| tqdm>=4.64.0 | |||
| # Logging ------------------------------------- | |||
| tensorboard>=2.4.1 | |||
| # wandb | |||
| # clearml | |||
| # Plotting ------------------------------------ | |||
| pandas>=1.1.4 | |||
| seaborn>=0.11.0 | |||
| # Export -------------------------------------- | |||
| # coremltools>=5.2 # CoreML export | |||
| # onnx>=1.9.0 # ONNX export | |||
| # onnx-simplifier>=0.4.1 # ONNX simplifier | |||
| # nvidia-pyindex # TensorRT export | |||
| # nvidia-tensorrt # TensorRT export | |||
| # scikit-learn==0.19.2 # CoreML quantization | |||
| # tensorflow>=2.4.1 # TFLite export (or tensorflow-cpu, tensorflow-aarch64) | |||
| # tensorflowjs>=3.9.0 # TF.js export | |||
| # openvino-dev # OpenVINO export | |||
| # Extras -------------------------------------- | |||
| # albumentations>=1.0.3 | |||
| # pycocotools>=2.0 # COCO mAP | |||
| # roboflow | |||
| opencv-python>=4.1.1 | |||
| maturin | |||
| @@ -50,20 +50,13 @@ async fn main() -> eyre::Result<()> { | |||
| ); | |||
| } | |||
| run( | |||
| get_python_path().context("Could not get pip binary")?, | |||
| &["-m", "pip", "install", "--upgrade", "pip"], | |||
| None, | |||
| ) | |||
| .await | |||
| .context("failed to install pip")?; | |||
| run( | |||
| get_pip_path().context("Could not get pip binary")?, | |||
| &["install", "-r", "requirements.txt"], | |||
| None, | |||
| &["install", "maturin"], | |||
| Some(venv), | |||
| ) | |||
| .await | |||
| .context("pip install failed")?; | |||
| .context("pip install maturin failed")?; | |||
| run( | |||
| "maturin", | |||
| @@ -81,6 +74,16 @@ async fn main() -> eyre::Result<()> { | |||
| async fn run_dataflow(dataflow: &Path) -> eyre::Result<()> { | |||
| let cargo = std::env::var("CARGO").unwrap(); | |||
| // First build the dataflow (install requirements) | |||
| let mut cmd = tokio::process::Command::new(&cargo); | |||
| cmd.arg("run"); | |||
| cmd.arg("--package").arg("dora-cli"); | |||
| cmd.arg("--").arg("build").arg(dataflow); | |||
| if !cmd.status().await?.success() { | |||
| bail!("failed to run dataflow"); | |||
| }; | |||
| let mut cmd = tokio::process::Command::new(&cargo); | |||
| cmd.arg("run"); | |||
| cmd.arg("--package").arg("dora-cli"); | |||
| @@ -1,82 +0,0 @@ | |||
| LABELS = [ | |||
| "ABC", | |||
| "bicycle", | |||
| "car", | |||
| "motorcycle", | |||
| "airplane", | |||
| "bus", | |||
| "train", | |||
| "truck", | |||
| "boat", | |||
| "traffic light", | |||
| "fire hydrant", | |||
| "stop sign", | |||
| "parking meter", | |||
| "bench", | |||
| "bird", | |||
| "cat", | |||
| "dog", | |||
| "horse", | |||
| "sheep", | |||
| "cow", | |||
| "elephant", | |||
| "bear", | |||
| "zebra", | |||
| "giraffe", | |||
| "backpack", | |||
| "umbrella", | |||
| "handbag", | |||
| "tie", | |||
| "suitcase", | |||
| "frisbee", | |||
| "skis", | |||
| "snowboard", | |||
| "sports ball", | |||
| "kite", | |||
| "baseball bat", | |||
| "baseball glove", | |||
| "skateboard", | |||
| "surfboard", | |||
| "tennis racket", | |||
| "bottle", | |||
| "wine glass", | |||
| "cup", | |||
| "fork", | |||
| "knife", | |||
| "spoon", | |||
| "bowl", | |||
| "banana", | |||
| "apple", | |||
| "sandwich", | |||
| "orange", | |||
| "broccoli", | |||
| "carrot", | |||
| "hot dog", | |||
| "pizza", | |||
| "donut", | |||
| "cake", | |||
| "chair", | |||
| "couch", | |||
| "potted plant", | |||
| "bed", | |||
| "dining table", | |||
| "toilet", | |||
| "tv", | |||
| "laptop", | |||
| "mouse", | |||
| "remote", | |||
| "keyboard", | |||
| "cell phone", | |||
| "microwave", | |||
| "oven", | |||
| "toaster", | |||
| "sink", | |||
| "refrigerator", | |||
| "book", | |||
| "clock", | |||
| "vase", | |||
| "scissors", | |||
| "teddy bear", | |||
| "hair drier", | |||
| "toothbrush", | |||
| ] | |||
| @@ -1,52 +0,0 @@ | |||
| #!/usr/bin/env python3 | |||
| # -*- coding: utf-8 -*- | |||
| import os | |||
| import time | |||
| import numpy as np | |||
| import cv2 | |||
| from dora import Node | |||
| node = Node() | |||
| CAMERA_INDEX = int(os.getenv("CAMERA_INDEX", 0)) | |||
| CAMERA_WIDTH = 640 | |||
| CAMERA_HEIGHT = 480 | |||
| video_capture = cv2.VideoCapture(CAMERA_INDEX) | |||
| font = cv2.FONT_HERSHEY_SIMPLEX | |||
| start = time.time() | |||
| # Run for 20 seconds | |||
| while time.time() - start < 10: | |||
| # Wait next dora_input | |||
| event = node.next() | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| ret, frame = video_capture.read() | |||
| if not ret: | |||
| frame = np.zeros((CAMERA_HEIGHT, CAMERA_WIDTH, 3), dtype=np.uint8) | |||
| cv2.putText( | |||
| frame, | |||
| "No Webcam was found at index %d" % (CAMERA_INDEX), | |||
| (int(30), int(30)), | |||
| font, | |||
| 0.75, | |||
| (255, 255, 255), | |||
| 2, | |||
| 1, | |||
| ) | |||
| node.send_output( | |||
| "image", | |||
| cv2.imencode(".jpg", frame)[1].tobytes(), | |||
| event["metadata"], | |||
| ) | |||
| elif event_type == "STOP": | |||
| print("received stop") | |||
| break | |||
| else: | |||
| print("received unexpected event:", event_type) | |||
| break | |||
| video_capture.release() | |||
| @@ -0,0 +1,88 @@ | |||
| ## Dora Node Hub | |||
| This hub contains useful pre-built nodes for Dora. | |||
| # Structure | |||
| The structure of the node hub is as follows (please use the same structure if you need to add a new node): | |||
| ``` | |||
| node-hub/ | |||
| └── your-node/ | |||
| ├── main.py | |||
| ├── README.mdr | |||
| └── pyproject.toml | |||
| ``` | |||
| The idea is to make a `pyproject.toml` file that will install the required dependencies for the node **and** attach main | |||
| function of the node inside a callable script in your environment. | |||
| To do so, you will need to add a `main` function inside the `main.py` file. | |||
| ```python | |||
| def main(): | |||
| pass | |||
| ``` | |||
| And then you will need to adapt the following `pyproject.toml` file: | |||
| ```toml | |||
| [tool.poetry] | |||
| name = "[name of the node e.g. video-encoder, with '-' to replace spaces]" | |||
| version = "0.1" | |||
| authors = ["[Pseudo/Name] <[email]>"] | |||
| description = "Dora Node for []" | |||
| readme = "README.md" | |||
| packages = [ | |||
| { include = "main.py", to = "[name of the node with '_' to replace spaces]" } | |||
| ] | |||
| [tool.poetry.dependencies] | |||
| python = "^3.11" | |||
| dora-rs = "0.3.5" | |||
| ... [add your dependencies here] ... | |||
| [tool.poetry.scripts] | |||
| [name of the node with '-' to replace spaces] = "[name of the node with '_' to replace spaces].main:main" | |||
| [build-system] | |||
| requires = ["poetry-core>=1.0.0"] | |||
| build-backend = "poetry.core.masonry.api" | |||
| ``` | |||
| Finally, the README.md file should explicit all inputs/outputs of the node and how to configure it in the YAML file. | |||
| # Example | |||
| ```toml | |||
| [tool.poetry] | |||
| name = "opencv-plot" | |||
| version = "0.1" | |||
| authors = [ | |||
| "Haixuan Xavier Tao <tao.xavier@outlook.com>", | |||
| "Enzo Le Van <dev@enzo-le-van.fr>" | |||
| ] | |||
| description = "Dora Node for plotting data with OpenCV" | |||
| readme = "README.md" | |||
| packages = [ | |||
| { include = "main.py", to = "opencv_plot" } | |||
| ] | |||
| [tool.poetry.dependencies] | |||
| python = "^3.11" | |||
| dora-rs = "^0.3.5" | |||
| opencv-python = "^4.10.0.84" | |||
| [tool.poetry.scripts] | |||
| opencv-plot = "opencv_plot.main:main" | |||
| [build-system] | |||
| requires = ["poetry-core>=1.0.0"] | |||
| build-backend = "poetry.core.masonry.api" | |||
| ``` | |||
| ## License | |||
| This project is licensed under Apache-2.0. Check out [NOTICE.md](../NOTICE.md) for more information. | |||
| @@ -0,0 +1,74 @@ | |||
| # Dora Node for plotting data with OpenCV | |||
| This node is used to plot a text and a list of bbox on a base image (ideal for object detection). | |||
| # YAML | |||
| ```yaml | |||
| - id: opencv-plot | |||
| build: pip install ../../node-hub/opencv-plot | |||
| path: opencv-plot | |||
| inputs: | |||
| # image: Arrow array of size 1 containing the base image | |||
| # bbox: Arrow array of bbox | |||
| # text: Arrow array of size 1 containing the text to be plotted | |||
| env: | |||
| PLOT_WIDTH: 640 # optional, default is image input width | |||
| PLOT_HEIGHT: 480 # optional, default is image input height | |||
| ``` | |||
| # Inputs | |||
| - `image`: Arrow array containing the base image | |||
| ```python | |||
| image: { | |||
| "width": np.uint32, | |||
| "height": np.uint32, | |||
| "encoding": bytes, | |||
| "data": np.array # flattened image data | |||
| } | |||
| encoded_image = pa.array([image]) | |||
| decoded_image = { | |||
| "width": np.uint32(encoded_image[0]["width"]), | |||
| "height": np.uint32(encoded_image[0]["height"]), | |||
| "encoding": encoded_image[0]["encoding"].as_py(), | |||
| "data": encoded_image[0]["data"].values.to_numpy().astype(np.uint8) | |||
| } | |||
| ``` | |||
| - `bbox`: an arrow array containing the bounding boxes, confidence scores, and class names of the detected objects | |||
| ```Python | |||
| bbox: { | |||
| "bbox": np.array, # flattened array of bounding boxes | |||
| "conf": np.array, # flat array of confidence scores | |||
| "names": np.array, # flat array of class names | |||
| } | |||
| encoded_bbox = pa.array([bbox]) | |||
| decoded_bbox = { | |||
| "bbox": encoded_bbox[0]["bbox"].values.to_numpy().reshape(-1, 3), | |||
| "conf": encoded_bbox[0]["conf"].values.to_numpy(), | |||
| "names": encoded_bbox[0]["names"].values.to_numpy(zero_copy_only=False), | |||
| } | |||
| ``` | |||
| - `text`: Arrow array containing the text to be plotted | |||
| ```python | |||
| text: str | |||
| encoded_text = pa.array([text]) | |||
| decoded_text = encoded_text[0].as_py() | |||
| ``` | |||
| ## License | |||
| This project is licensed under Apache-2.0. Check out [NOTICE.md](../../NOTICE.md) for more information. | |||
| @@ -0,0 +1,171 @@ | |||
| import os | |||
| import argparse | |||
| import cv2 | |||
| import numpy as np | |||
| import pyarrow as pa | |||
| from dora import Node | |||
| RUNNER_CI = True if os.getenv("CI") == "true" else False | |||
| class Plot: | |||
| frame: np.array = np.array([]) | |||
| bboxes: {} = { | |||
| "bbox": np.array([]), | |||
| "conf": np.array([]), | |||
| "names": np.array([]), | |||
| } | |||
| text: str = "" | |||
| width: np.uint32 = None | |||
| height: np.uint32 = None | |||
| def plot_frame(plot): | |||
| for bbox in zip(plot.bboxes["bbox"], plot.bboxes["conf"], plot.bboxes["names"]): | |||
| [ | |||
| [min_x, min_y, max_x, max_y], | |||
| confidence, | |||
| label, | |||
| ] = bbox | |||
| cv2.rectangle( | |||
| plot.frame, | |||
| (int(min_x), int(min_y)), | |||
| (int(max_x), int(max_y)), | |||
| (0, 255, 0), | |||
| 2, | |||
| ) | |||
| cv2.putText( | |||
| plot.frame, | |||
| f"{label}, {confidence:0.2f}", | |||
| (int(max_x) - 120, int(max_y) - 10), | |||
| cv2.FONT_HERSHEY_SIMPLEX, | |||
| 0.5, | |||
| (0, 255, 0), | |||
| 1, | |||
| 1, | |||
| ) | |||
| cv2.putText( | |||
| plot.frame, | |||
| plot.text, | |||
| (20, 20), | |||
| cv2.FONT_HERSHEY_SIMPLEX, | |||
| 0.5, | |||
| (255, 255, 255), | |||
| 1, | |||
| 1, | |||
| ) | |||
| if plot.width is not None and plot.height is not None: | |||
| plot.frame = cv2.resize(plot.frame, (plot.width, plot.height)) | |||
| if not RUNNER_CI: | |||
| if len(plot.frame.shape) >= 3: | |||
| cv2.imshow("Dora Node: opencv-plot", plot.frame) | |||
| def main(): | |||
| # Handle dynamic nodes, ask for the name of the node in the dataflow, and the same values as the ENV variables. | |||
| parser = argparse.ArgumentParser( | |||
| description="OpenCV Plotter: This node is used to plot text and bounding boxes on an image." | |||
| ) | |||
| parser.add_argument( | |||
| "--name", | |||
| type=str, | |||
| required=False, | |||
| help="The name of the node in the dataflow.", | |||
| default="opencv-plot", | |||
| ) | |||
| parser.add_argument( | |||
| "--plot-width", | |||
| type=int, | |||
| required=False, | |||
| help="The width of the plot.", | |||
| default=None, | |||
| ) | |||
| parser.add_argument( | |||
| "--plot-height", | |||
| type=int, | |||
| required=False, | |||
| help="The height of the plot.", | |||
| default=None, | |||
| ) | |||
| args = parser.parse_args() | |||
| plot_width = os.getenv("PLOT_WIDTH", args.plot_width) | |||
| plot_height = os.getenv("PLOT_HEIGHT", args.plot_height) | |||
| if plot_width is not None: | |||
| if isinstance(plot_width, str) and plot_width.isnumeric(): | |||
| plot_width = int(plot_width) | |||
| if plot_height is not None: | |||
| if isinstance(plot_height, str) and plot_height.isnumeric(): | |||
| plot_height = int(plot_height) | |||
| node = Node( | |||
| args.name | |||
| ) # provide the name to connect to the dataflow if dynamic node | |||
| plot = Plot() | |||
| plot.width = plot_width | |||
| plot.height = plot_height | |||
| pa.array([]) # initialize pyarrow array | |||
| for event in node: | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| event_id = event["id"] | |||
| if event_id == "image": | |||
| arrow_image = event["value"][0] | |||
| encoding = arrow_image["encoding"].as_py() | |||
| if encoding == "bgr8": | |||
| channels = 3 | |||
| storage_type = np.uint8 | |||
| else: | |||
| raise Exception(f"Unsupported image encoding: {encoding}") | |||
| image = { | |||
| "width": np.uint32(arrow_image["width"].as_py()), | |||
| "height": np.uint32(arrow_image["height"].as_py()), | |||
| "encoding": encoding, | |||
| "channels": channels, | |||
| "data": arrow_image["data"].values.to_numpy().astype(storage_type), | |||
| } | |||
| plot.frame = np.reshape( | |||
| image["data"], (image["height"], image["width"], image["channels"]) | |||
| ) | |||
| plot_frame(plot) | |||
| if not RUNNER_CI: | |||
| if cv2.waitKey(1) & 0xFF == ord("q"): | |||
| break | |||
| elif event_id == "bbox": | |||
| arrow_bbox = event["value"][0] | |||
| plot.bboxes = { | |||
| "bbox": arrow_bbox["bbox"].values.to_numpy().reshape(-1, 4), | |||
| "conf": arrow_bbox["conf"].values.to_numpy(), | |||
| "names": arrow_bbox["names"].values.to_numpy(zero_copy_only=False), | |||
| } | |||
| elif event_id == "text": | |||
| plot.text = event["value"][0].as_py() | |||
| elif event_type == "ERROR": | |||
| raise Exception(event["error"]) | |||
| if __name__ == "__main__": | |||
| main() | |||
| @@ -0,0 +1,23 @@ | |||
| [tool.poetry] | |||
| name = "opencv-plot" | |||
| version = "0.1" | |||
| authors = [ | |||
| "Haixuan Xavier Tao <tao.xavier@outlook.com>", | |||
| "Enzo Le Van <dev@enzo-le-van.fr>", | |||
| ] | |||
| description = "Dora Node for plotting text and bbox on image with OpenCV" | |||
| readme = "README.md" | |||
| packages = [{ include = "opencv_plot" }] | |||
| [tool.poetry.dependencies] | |||
| dora-rs = "0.3.5" | |||
| numpy = "< 2.0.0" | |||
| opencv-python = ">= 4.1.1" | |||
| [tool.poetry.scripts] | |||
| opencv-plot = "opencv_plot.main:main" | |||
| [build-system] | |||
| requires = ["poetry-core>=1.8.0"] | |||
| build-backend = "poetry.core.masonry.api" | |||
| @@ -0,0 +1,52 @@ | |||
| # Dora Node for capturing video with OpenCV | |||
| This node is used to capture video from a camera using OpenCV. | |||
| # YAML | |||
| ```yaml | |||
| - id: opencv-video-capture | |||
| build: pip install ../../node-hub/opencv-video-capture | |||
| path: opencv-video-capture | |||
| inputs: | |||
| tick: dora/timer/millis/16 # try to capture at 60fps | |||
| outputs: | |||
| - image: # the captured image | |||
| env: | |||
| PATH: 0 # optional, default is 0 | |||
| IMAGE_WIDTH: 640 # optional, default is video capture width | |||
| IMAGE_HEIGHT: 480 # optional, default is video capture height | |||
| ``` | |||
| # Inputs | |||
| - `tick`: empty Arrow array to trigger the capture | |||
| # Outputs | |||
| - `image`: an arrow array containing the captured image | |||
| ```Python | |||
| image: { | |||
| "width": np.uint32, | |||
| "height": np.uint32, | |||
| "encoding": str, | |||
| "data": np.array # flattened image data | |||
| } | |||
| encoded_image = pa.array([image]) | |||
| decoded_image = { | |||
| "width": np.uint32(encoded_image[0]["width"]), | |||
| "height": np.uint32(encoded_image[0]["height"]), | |||
| "encoding": encoded_image[0]["encoding"].as_py(), | |||
| "data": encoded_image[0]["data"].values.to_numpy().astype(np.uint8) | |||
| } | |||
| ``` | |||
| ## License | |||
| This project is licensed under Apache-2.0. Check out [NOTICE.md](../../NOTICE.md) for more information. | |||
| @@ -0,0 +1,122 @@ | |||
| import os | |||
| import argparse | |||
| import cv2 | |||
| import numpy as np | |||
| import pyarrow as pa | |||
| from dora import Node | |||
| import time | |||
| RUNNER_CI = True if os.getenv("CI") == "true" else False | |||
| def main(): | |||
| # Handle dynamic nodes, ask for the name of the node in the dataflow, and the same values as the ENV variables. | |||
| parser = argparse.ArgumentParser( | |||
| description="OpenCV Video Capture: This node is used to capture video from a camera." | |||
| ) | |||
| parser.add_argument( | |||
| "--name", | |||
| type=str, | |||
| required=False, | |||
| help="The name of the node in the dataflow.", | |||
| default="opencv-video-capture", | |||
| ) | |||
| parser.add_argument( | |||
| "--path", | |||
| type=int, | |||
| required=False, | |||
| help="The path of the device to capture (e.g. /dev/video1, or an index like 0, 1...", | |||
| default=0, | |||
| ) | |||
| parser.add_argument( | |||
| "--image-width", | |||
| type=int, | |||
| required=False, | |||
| help="The width of the image output. Default is the camera width.", | |||
| default=None, | |||
| ) | |||
| parser.add_argument( | |||
| "--image-height", | |||
| type=int, | |||
| required=False, | |||
| help="The height of the camera. Default is the camera height.", | |||
| default=None, | |||
| ) | |||
| args = parser.parse_args() | |||
| video_capture_path = os.getenv("CAPTURE_PATH", args.path) | |||
| if isinstance(video_capture_path, str) and video_capture_path.isnumeric(): | |||
| video_capture_path = int(video_capture_path) | |||
| video_capture = cv2.VideoCapture(video_capture_path) | |||
| image_width = os.getenv("IMAGE_WIDTH", args.image_width) | |||
| if image_width is not None: | |||
| if isinstance(image_width, str) and image_width.isnumeric(): | |||
| image_width = int(image_width) | |||
| video_capture.set(cv2.CAP_PROP_FRAME_WIDTH, image_width) | |||
| image_height = os.getenv("IMAGE_HEIGHT", args.image_height) | |||
| if image_height is not None: | |||
| if isinstance(image_height, str) and image_height.isnumeric(): | |||
| image_height = int(image_height) | |||
| video_capture.set(cv2.CAP_PROP_FRAME_HEIGHT, image_height) | |||
| node = Node(args.name) | |||
| start_time = time.time() | |||
| pa.array([]) # initialize pyarrow array | |||
| for event in node: | |||
| # Run this example in the CI for 20 seconds only. | |||
| if RUNNER_CI and time.time() - start_time > 20: | |||
| break | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| event_id = event["id"] | |||
| if event_id == "tick": | |||
| ret, frame = video_capture.read() | |||
| if not ret: | |||
| frame = np.zeros((480, 640, 3), dtype=np.uint8) | |||
| cv2.putText( | |||
| frame, | |||
| f"Error: no frame for camera at path {video_capture_path}.", | |||
| (int(30), int(30)), | |||
| cv2.FONT_HERSHEY_SIMPLEX, | |||
| 0.50, | |||
| (255, 255, 255), | |||
| 1, | |||
| 1, | |||
| ) | |||
| # resize the frame | |||
| if image_width is not None and image_height is not None: | |||
| frame = cv2.resize(frame, (image_width, image_height)) | |||
| image = { | |||
| "width": np.uint32(frame.shape[1]), | |||
| "height": np.uint32(frame.shape[0]), | |||
| "encoding": "bgr8", | |||
| "data": frame.ravel(), | |||
| } | |||
| node.send_output("image", pa.array([image]), event["metadata"]) | |||
| elif event_type == "ERROR": | |||
| raise Exception(event["error"]) | |||
| if __name__ == "__main__": | |||
| main() | |||
| @@ -0,0 +1,23 @@ | |||
| [tool.poetry] | |||
| name = "opencv-video-capture" | |||
| version = "0.1" | |||
| authors = [ | |||
| "Haixuan Xavier Tao <tao.xavier@outlook.com>", | |||
| "Enzo Le Van <dev@enzo-le-van.fr>", | |||
| ] | |||
| description = "Dora Node for capturing video with OpenCV" | |||
| readme = "README.md" | |||
| packages = [{ include = "opencv_video_capture" }] | |||
| [tool.poetry.dependencies] | |||
| dora-rs = "0.3.5" | |||
| numpy = "< 2.0.0" | |||
| opencv-python = ">= 4.1.1" | |||
| [tool.poetry.scripts] | |||
| opencv-video-capture = "opencv_video_capture.main:main" | |||
| [build-system] | |||
| requires = ["poetry-core>=1.8.0"] | |||
| build-backend = "poetry.core.masonry.api" | |||
| @@ -0,0 +1,66 @@ | |||
| # Dora Node for detecting objects in images using YOLOv8 | |||
| This node is used to detect objects in images using YOLOv8. | |||
| # YAML | |||
| ```yaml | |||
| - id: object_detection | |||
| build: pip install ../../node-hub/ultralytics-yolo | |||
| path: ultralytics-yolo | |||
| inputs: | |||
| image: webcam/image | |||
| outputs: | |||
| - bbox | |||
| env: | |||
| MODEL: yolov5n.pt | |||
| ``` | |||
| # Inputs | |||
| - `image`: Arrow array containing the base image | |||
| ```python | |||
| image: { | |||
| "width": np.uint32, | |||
| "height": np.uint32, | |||
| "encoding": str, | |||
| "data": np.array # flattened image data | |||
| } | |||
| encoded_image = pa.array([image]) | |||
| decoded_image = { | |||
| "width": np.uint32(encoded_image[0]["width"]), | |||
| "height": np.uint32(encoded_image[0]["height"]), | |||
| "encoding": encoded_image[0]["encoding"].as_py(), | |||
| "data": encoded_image[0]["data"].values.to_numpy().astype(np.uint8) | |||
| } | |||
| ``` | |||
| # Outputs | |||
| - `bbox`: an arrow array containing the bounding boxes, confidence scores, and class names of the detected objects | |||
| ```Python | |||
| bbox: { | |||
| "bbox": np.array, # flattened array of bounding boxes | |||
| "conf": np.array, # flat array of confidence scores | |||
| "names": np.array, # flat array of class names | |||
| } | |||
| encoded_bbox = pa.array([bbox]) | |||
| decoded_bbox = { | |||
| "bbox": encoded_bbox[0]["bbox"].values.to_numpy().reshape(-1, 3), | |||
| "conf": encoded_bbox[0]["conf"].values.to_numpy(), | |||
| "names": encoded_bbox[0]["names"].values.to_numpy(zero_copy_only=False), | |||
| } | |||
| ``` | |||
| ## License | |||
| This project is licensed under Apache-2.0. Check out [NOTICE.md](../../NOTICE.md) for more information. | |||
| @@ -0,0 +1,23 @@ | |||
| [tool.poetry] | |||
| name = "ultralytics-yolo" | |||
| version = "0.1" | |||
| authors = [ | |||
| "Haixuan Xavier Tao <tao.xavier@outlook.com>", | |||
| "Enzo Le Van <dev@enzo-le-van.fr>", | |||
| ] | |||
| description = "Dora Node for object detection with Ultralytics YOLOv8" | |||
| readme = "README.md" | |||
| packages = [{ include = "ultralytics_yolo" }] | |||
| [tool.poetry.dependencies] | |||
| dora-rs = "0.3.5" | |||
| numpy = "< 2.0.0" | |||
| ultralytics = "<= 8.2.52" | |||
| [tool.poetry.scripts] | |||
| ultralytics-yolo = "ultralytics_yolo.main:main" | |||
| [build-system] | |||
| requires = ["poetry-core>=1.8.0"] | |||
| build-backend = "poetry.core.masonry.api" | |||
| @@ -0,0 +1,97 @@ | |||
| import os | |||
| import argparse | |||
| import numpy as np | |||
| import pyarrow as pa | |||
| from dora import Node | |||
| from ultralytics import YOLO | |||
| def main(): | |||
| # Handle dynamic nodes, ask for the name of the node in the dataflow, and the same values as the ENV variables. | |||
| parser = argparse.ArgumentParser( | |||
| description="UltraLytics YOLO: This node is used to perform object detection using the UltraLytics YOLO model." | |||
| ) | |||
| parser.add_argument( | |||
| "--name", | |||
| type=str, | |||
| required=False, | |||
| help="The name of the node in the dataflow.", | |||
| default="ultralytics-yolo", | |||
| ) | |||
| parser.add_argument( | |||
| "--model", | |||
| type=str, | |||
| required=False, | |||
| help="The name of the model file (e.g. yolov8n.pt).", | |||
| default="yolov8n.pt", | |||
| ) | |||
| args = parser.parse_args() | |||
| model_path = os.getenv("MODEL", args.model) | |||
| model = YOLO(model_path) | |||
| node = Node(args.name) | |||
| pa.array([]) # initialize pyarrow array | |||
| for event in node: | |||
| event_type = event["type"] | |||
| if event_type == "INPUT": | |||
| event_id = event["id"] | |||
| if event_id == "image": | |||
| arrow_image = event["value"][0] | |||
| encoding = arrow_image["encoding"].as_py() | |||
| if encoding == "bgr8": | |||
| channels = 3 | |||
| storage_type = np.uint8 | |||
| else: | |||
| raise Exception(f"Unsupported image encoding: {encoding}") | |||
| image = { | |||
| "width": np.uint32(arrow_image["width"].as_py()), | |||
| "height": np.uint32(arrow_image["height"].as_py()), | |||
| "encoding": encoding, | |||
| "channels": channels, | |||
| "data": arrow_image["data"].values.to_numpy().astype(storage_type), | |||
| } | |||
| frame = image["data"].reshape( | |||
| (image["height"], image["width"], image["channels"]) | |||
| ) | |||
| if encoding == "bgr8": | |||
| frame = frame[:, :, ::-1] # OpenCV image (BGR to RGB) | |||
| results = model(frame, verbose=False) # includes NMS | |||
| bboxes = np.array(results[0].boxes.xyxy.cpu()) | |||
| conf = np.array(results[0].boxes.conf.cpu()) | |||
| labels = np.array(results[0].boxes.cls.cpu()) | |||
| names = [model.names.get(label) for label in labels] | |||
| bbox = { | |||
| "bbox": bboxes.ravel(), | |||
| "conf": conf, | |||
| "names": names, | |||
| } | |||
| node.send_output( | |||
| "bbox", | |||
| pa.array([bbox]), | |||
| event["metadata"], | |||
| ) | |||
| elif event_type == "ERROR": | |||
| raise Exception(event["error"]) | |||
| if __name__ == "__main__": | |||
| main() | |||