Skip to content

Commit

Permalink
Add ios lidar (#762)
Browse files Browse the repository at this point in the history
This PR add the possibility to work with IOS lidar as well as texture
rgb-d image within rerun

<img width="1800" alt="Screenshot 2025-01-22 at 09 20 50"
src="https://github.com/user-attachments/assets/97ec6efe-db79-437b-9b4b-6f254da38333"
/>
  • Loading branch information
haixuanTao authored Jan 22, 2025
2 parents 0fa5863 + 91e291d commit 18d26d1
Show file tree
Hide file tree
Showing 12 changed files with 288 additions and 63 deletions.
16 changes: 16 additions & 0 deletions examples/depth_camera/ios-dev.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
nodes:
- id: camera
build: pip install -e ../../node-hub/dora-ios-lidar
path: dora-ios-lidar
inputs:
tick: dora/timer/millis/20
outputs:
- image
- depth

- id: plot
build: pip install -e ../../node-hub/dora-rerun
path: dora-rerun
inputs:
image: camera/image
depth: camera/depth
16 changes: 16 additions & 0 deletions examples/depth_camera/ios.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
nodes:
- id: camera
build: pip install dora-ios-lidar
path: dora-ios-lidar
inputs:
tick: dora/timer/millis/20
outputs:
- image
- depth

- id: plot
build: pip install dora-rerun
path: dora-rerun
inputs:
image: camera/image
depth: camera/depth
Original file line number Diff line number Diff line change
@@ -1,20 +1,17 @@
nodes:
- id: camera
build: pip install -e ../../node-hub/dora-pyrealsense
path: dora-pyrealsense
path: sudo
args: dora-pyrealsense
inputs:
tick: dora/timer/millis/20
outputs:
- image
- depth
env:
IMAGE_WIDTH: 640
IMAGE_HEIGHT: 480

- id: plot
build: pip install -e ../../node-hub/dora-rerun
path: dora-rerun
inputs:
image: camera/image
world/camera/depth: camera/depth

16 changes: 16 additions & 0 deletions examples/depth_camera/realsense.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
nodes:
- id: camera
build: pip install dora-pyrealsense
path: dora-pyrealsense
inputs:
tick: dora/timer/millis/20
outputs:
- image
- depth

- id: plot
build: pip install dora-rerun
path: dora-rerun
inputs:
image: camera/image
depth: camera/depth
20 changes: 0 additions & 20 deletions examples/realsense/camera.yaml

This file was deleted.

40 changes: 40 additions & 0 deletions node-hub/dora-ios-lidar/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
# dora-ios-lidar

## Getting started

- Install it with pip:

```bash
pip install -e .
```

- Make sure to install `record3d` app on your IOS device.
- Buy the USB connection package to start streaming on USB.

## Contribution Guide

- Format with [ruff](https://docs.astral.sh/ruff/):

```bash
ruff check . --fix
```

- Lint with ruff:

```bash
ruff check .
```

- Test with [pytest](https://github.com/pytest-dev/pytest)

```bash
pytest . # Test
```

## YAML Specification

## Examples

## License

dora-ios-lidar's code are released under the MIT License
11 changes: 11 additions & 0 deletions node-hub/dora-ios-lidar/dora_ios_lidar/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
import os

# Define the path to the README file relative to the package directory
readme_path = os.path.join(os.path.dirname(os.path.dirname(__file__)), "README.md")

# Read the content of the README file
try:
with open(readme_path, "r", encoding="utf-8") as f:
__doc__ = f.read()
except FileNotFoundError:
__doc__ = "README file not found."
5 changes: 5 additions & 0 deletions node-hub/dora-ios-lidar/dora_ios_lidar/__main__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
from .main import main


if __name__ == "__main__":
main()
109 changes: 109 additions & 0 deletions node-hub/dora-ios-lidar/dora_ios_lidar/main.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
from threading import Event

import cv2
import numpy as np
import pyarrow as pa
from dora import Node
from record3d import Record3DStream


class DemoApp:
def __init__(self):
self.event = Event()
self.session = None
self.DEVICE_TYPE__TRUEDEPTH = 0
self.DEVICE_TYPE__LIDAR = 1
self.stop = False

def on_new_frame(self):
"""
This method is called from non-main thread, therefore cannot be used for presenting UI.
"""
self.event.set() # Notify the main thread to stop waiting and process new frame.

def on_stream_stopped(self):
self.stop = True
print("Stream stopped")

def connect_to_device(self, dev_idx):
print("Searching for devices")
devs = Record3DStream.get_connected_devices()
print("{} device(s) found".format(len(devs)))
for dev in devs:
print("\tID: {}\n".format(dev.product_id))

if len(devs) <= dev_idx:
raise RuntimeError(
"Cannot connect to device #{}, try different index.".format(dev_idx)
)

dev = devs[dev_idx]
self.session = Record3DStream()
self.session.on_new_frame = self.on_new_frame
self.session.on_stream_stopped = self.on_stream_stopped
self.session.connect(dev) # Initiate connection and start capturing

def get_intrinsic_mat_from_coeffs(self, coeffs):
return np.array(
[[coeffs.fx, 0, coeffs.tx], [0, coeffs.fy, coeffs.ty], [0, 0, 1]]
)

def start_processing_stream(self):
node = Node()

for event in node:
if self.stop:
break
if event["type"] == "INPUT":
if event["id"] == "TICK":
self.event.wait() # Wait for new frame to arrive

# Copy the newly arrived RGBD frame
depth = self.session.get_depth_frame()
rgb = self.session.get_rgb_frame()
intrinsic_mat = self.get_intrinsic_mat_from_coeffs(
self.session.get_intrinsic_mat()
)

if depth.shape != rgb.shape:
rgb = cv2.resize(rgb, (depth.shape[1], depth.shape[0]))

node.send_output(
"image",
pa.array(rgb.ravel()),
metadata={
"encoding": "rgb8",
"width": rgb.shape[1],
"height": rgb.shape[0],
},
)

node.send_output(
"depth",
pa.array(depth.ravel().astype(np.float64())),
metadata={
"width": depth.shape[1],
"height": depth.shape[0],
"encoding": "CV_64F",
"focal": [
int(intrinsic_mat[0, 0]),
int(intrinsic_mat[1, 1]),
],
"resolution": [
int(intrinsic_mat[0, 2]),
int(intrinsic_mat[1, 2]),
],
},
)

self.event.clear()


def main():
app = DemoApp()
app.connect_to_device(dev_idx=0)
app.start_processing_stream()


if __name__ == "__main__":
main()
20 changes: 20 additions & 0 deletions node-hub/dora-ios-lidar/pyproject.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
[project]
name = "dora-ios-lidar"
version = "0.0.0"
authors = [{ name = "Your Name", email = "[email protected]" }]
description = "dora-ios-lidar"
license = { text = "MIT" }
readme = "README.md"
requires-python = ">=3.8"

dependencies = [
"dora-rs >= 0.3.6",
"opencv-python>=4.11.0.86",
"record3d>=1.4",
]

[dependency-groups]
dev = ["pytest >=8.1.1", "ruff >=0.9.1"]

[project.scripts]
dora-ios-lidar = "dora_ios_lidar.main:main"
9 changes: 9 additions & 0 deletions node-hub/dora-ios-lidar/tests/test_dora_ios_lidar.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
import pytest


def test_import_main():
from dora_ios_lidar.main import main

# Check that everything is working, and catch dora Runtime Exception as we're not running in a dora dataflow.
with pytest.raises(RuntimeError):
main()
Loading

0 comments on commit 18d26d1

Please sign in to comment.