Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -141,3 +141,18 @@ Afterwards, navigate to desired application as listed below
</td>
</tr>
</table>

### [⚙️ Dynamic Calibration](dynamic-calibration/)

<table>
<tr>
<td width="50%" valign="top">
<img src="dynamic-calibration/media/dcl.gif" alt="Dynamic Calibration">
</td>
<td width="50%" valign="middle" align="center">
Example of showing off the dynamic recalibration in action
<br><br>
<a href="dynamic-calibration/">⚙️ Dynamic calibration</a>
</td>
</tr>
</table>
37 changes: 37 additions & 0 deletions dynamic-calibration/.oakappignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# Python virtual environments
venv/
.venv/

# Node.js
# ignore node_modules, it will be reinstalled in the container
node_modules/

# Multimedia files
media/

# Documentation
README.md

# VCS
.git/
.github/
.gitlab/

# Ignore specific files in utils/
utils/dynamic_calibration_interative.py
utils/helper_functions.py

# The following files are ignored by default
# uncomment a line if you explicitly need it

# !*.oakapp

# Python
# !**/.mypy_cache/
# !**/.ruff_cache/

# IDE files
# !**/.idea
# !**/.vscode
# !**/.zed

116 changes: 116 additions & 0 deletions dynamic-calibration/README.md
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Check out other examples for the overall structure of README (what headings to use, what is under which heading, ...). Overall the goal would be that all examples are structured in the same way but you can add some extra headings if you see the need for it

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Will do, saw that you have intermediate readMe to explain on which platforms its supported

Original file line number Diff line number Diff line change
@@ -0,0 +1,116 @@
# Stereo Dynamic Calibration

This example demonstrates **runtime stereo camera calibration** with the `DynamicCalibration` node, plus a host-side controller/visualizer that overlays helpful UI (help panel, coverage bar, quality/recalibration modals, and a depth ROI HUD).

> Works in **peripheral mode**: the device performs calibration; the host sends commands and renders overlays.
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So it doesn't work in standalone? Just curious: What is the limitation?

If that is the case (that it doesn't work in standalone) then we should remove the .oakappignore and oakapp.toml files as those are only needed for standalone apps

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What do you mean by that?
It is a hostNode, so that the Dynamic recalibration is mostly performed on the host itself.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think @klemen1999 meant that there is written

Works in peripheral mode: the device performs calibration; the host sends commands and renders overlays.

Which implies as if it was not working for standalone mode (the second mode to peripheral mode).


## Features

- **Interactive commands**: start/force recalibration, load images, run quality checks, apply/rollback calibrations, and **flash** (EEPROM) new/previous/factory calibration.
- **Coverage bar**: centered, large progress bar while collecting frames (or briefly after `l`).
- **Quality modal**: big 3-color bar (GOOD / COULD BE IMPROVED / NEEDS RECALIBRATION) with a pointer based on rotation change and a summary of depth-error deltas.
- **Recalibration modal**: summary with Euler angle deltas and depth-error deltas; prompts to flash if there is a significant change.
- **Depth HUD**: optional, shows depth/disp at a movable ROI (center + mean), with a small “tiny box” indicator.
- **Always-on help panel** (toggleable).

## Demo

<p align="center">
<img src="media/dcl.gif" alt="demo" />
</p>

## Requirements

- A **Luxonis device** connected via USB/Ethernet.
- Packages:
- `depthai`
- `depthai-nodes`
- `opencv-python`
- `numpy`

Install via:

```bash
pip install -r requirements.txt
```

## Run

```bash
python3 main.py
# or
python3 main.py --fps_limit 10
# or
python3 main.py --device 18443010C1BA9D1200
```

When launched, the app starts a RemoteConnection server. Open the visualizer at:

```
http://localhost:8082
```

Replace `localhost` with your host IP if viewing from another machine.

## Controls

Use these keys while the app is running (focus the browser visualizer window):

| Key | Action |
| ----------- | ---------------------------------------------------------------------------------------- |
| `q` | Quit the app |
| `h` | Toggle help panel |
| `g` | Toggle Depth HUD (ROI readout) |
| `r` | Start recalibration |
| `d` | **Force** recalibration |
| `l` | Load image(s) for calibration (shows coverage bar for ~2s) |
| `c` | Calibration quality check |
| `v` | **Force** calibration quality check |
| `n` | Apply **NEW** calibration (when available) |
| `o` | Apply **PREVIOUS** calibration (rollback) |
| `p` | **Flash NEW/current** calibration to EEPROM |
| `k` | **Flash PREVIOUS** calibration to EEPROM |
| `f` | **Flash FACTORY** calibration to EEPROM |
| `w / a / s` | Move ROI up/left/down (Depth HUD).<br>**Note:** `d` is reserved for *Force recalibrate*. |
| `z / x` | ROI size − / + |

> **Status banners** appear in the **center** after critical actions (e.g., applying/ flashing calibration) and auto-hide after ~2s.\
> **Modals** (quality/recalibration) also appear centered and auto-hide after ~3.5s or on any key press.

## On‑screen UI Cheat Sheet

- **Help panel** (top-left): quick reference of all keys (toggle with `h`).
- **Coverage bar** (center): big progress bar while collecting frames; also shown briefly (≈2s) after pressing `l`.
- **Quality modal** (center): three colored segments (green/yellow/red) with a **downward** pointer (`▼`) indicating rotation-change severity; optional line with depth-error deltas (@1m/2m/5m/10m).
- **Recalibration modal** (center): “Recalibration complete”, significant-axis warning (if any), Euler angles, and depth-error deltas; suggests flashing if the change is significant.
- **Depth HUD** (inline): shows depth/disp at the ROI center and mean within a tiny box; move with `w/a/s` (and resize with `z/x`).

## Output (console)

- **Coverage**: per-cell coverage and acquisition status when emitted by the device.
- **Calibration results**: prints when a new calibration is produced and shows deltas:
- Rotation delta `|| r_current - r_new ||` in degrees,
- Mean Sampson error (new vs. current),
- Theoretical **Depth Error Difference** at 1/2/5/10 meters.
- **Quality checks**: same metrics as above without actually applying a new calibration.

## Tips & Notes

- To **flash** (EEPROM) from the UI you must pass the `device` into the controller (`dyn_ctrl.set_device(device)`).
- If you link **disparity** instead of **depth** to the controller, call `dyn_ctrl.set_depth_units_is_mm(False)` so the HUD labels use “Disp” instead of meters.
- The coverage percentage accepts either `[0..1]` or `[0..100]` from the device; the controller auto-detects and normalizes.
- The **Collecting frames** bar hides automatically 2s after pressing `l`; during active recalibration (`r`/`d`) it stays up until calibration finishes.

## Installation (dev quick start)

```bash
python3 -m venv .venv
source .venv/bin/activate
pip install -U pip
pip install -r requirements.txt
python3 main.py
```

______________________________________________________________________

If you use this as a base for your own app, the heart of the UX is `utils/dynamic_controler.py` — it wires `DynamicCalibration` queues and renders all overlays via `ImgAnnotations` so you don’t need `cv2.imshow()`.
86 changes: 86 additions & 0 deletions dynamic-calibration/main.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
import cv2

from depthai_nodes.node import ApplyColormap
import depthai as dai

from utils.dynamic_controler import DynamicCalibrationControler
from utils.arguments import initialize_argparser

_, args = initialize_argparser()

visualizer = dai.RemoteConnection(httpPort=8082)
device = dai.Device(dai.DeviceInfo(args.device)) if args.device else dai.Device()
# ---------- Pipeline definition ----------
with dai.Pipeline(device) as pipeline:
# Create camera nodes
cam_left = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_B)
cam_right = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_C)

# Request full resolution NV12 outputs
left_out = cam_left.requestFullResolutionOutput(
dai.ImgFrame.Type.NV12, fps=args.fps_limit
)
right_out = cam_right.requestFullResolutionOutput(
dai.ImgFrame.Type.NV12, fps=args.fps_limit
)

# Stereo node
stereo = pipeline.create(dai.node.StereoDepth)
left_out.link(stereo.left)
right_out.link(stereo.right)

# Dynamic calibration node
dyn_calib = pipeline.create(dai.node.DynamicCalibration)
left_out.link(dyn_calib.left)
right_out.link(dyn_calib.right)

# Output queues
depth_parser = pipeline.create(ApplyColormap).build(stereo.disparity)
# depth_parser.setMaxValue(int(stereo.initialConfig.getMaxDisparity())) # NOTE: Uncomment when DAI fixes a bug
depth_parser.setColormap(cv2.COLORMAP_JET)

calibration = device.readCalibration()
new_calibration = None
old_calibration = None

# --- existing ---
calibration_output = dyn_calib.calibrationOutput.createOutputQueue()
coverage_output = dyn_calib.coverageOutput.createOutputQueue()
quality_output = dyn_calib.qualityOutput.createOutputQueue()
input_control = dyn_calib.inputControl.createInputQueue()
device.setCalibration(calibration)

# ---------- Visualizer setup ----------
visualizer.addTopic("Left", stereo.syncedLeft, "images")
visualizer.addTopic("Right", stereo.syncedRight, "images")
visualizer.addTopic("Depth", depth_parser.out, "images")

dyn_ctrl = pipeline.create(DynamicCalibrationControler).build(
preview=depth_parser.out, # for timestamped overlays
depth=stereo.depth, # raw uint16 depth in mm
)
visualizer.addTopic("DynCalib HUD", dyn_ctrl.out_annotations, "images")

pipeline.start()
visualizer.registerPipeline(pipeline)

# give it queues
dyn_ctrl.set_coverage_output(coverage_output)
dyn_ctrl.set_calibration_output(calibration_output)
dyn_ctrl.set_command_input(input_control)
dyn_ctrl.set_quality_output(quality_output)
dyn_ctrl.set_depth_units_is_mm(True) # True for stereo.depth, False for disparity
dyn_ctrl.set_device(device)

# (optional) Set current calibration
try:
dyn_ctrl.set_current_calibration(device.readCalibration())
except Exception:
pass

while pipeline.isRunning():
key = visualizer.waitKey(1)
if key != -1:
dyn_ctrl.handle_key_press(key)
if dyn_ctrl.wants_quit:
break
Binary file added dynamic-calibration/media/dcl.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
15 changes: 15 additions & 0 deletions dynamic-calibration/oakapp.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
identifier = "com.example.dynamic-calibration"
app_version = "1.0.0"

prepare_container = [
{ type = "RUN", command = "apt-get update" },
{ type = "RUN", command = "apt-get install -y python3-pip" },
{ type = "COPY", source = "requirements.txt", target = "requirements.txt" },
{ type = "RUN", command = "pip3 install -r /app/requirements.txt --break-system-packages" },
]

prepare_build_container = []

build_steps = []

entrypoint = ["bash", "-c", "python3 -u /app/main.py"]
6 changes: 6 additions & 0 deletions dynamic-calibration/requirements.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
--extra-index-url https://artifacts.luxonis.com/artifactory/luxonis-python-snapshot-local
depthai==3.0.0
depthai-nodes==0.3.4
numpy>=1.22
opencv-python==4.10.0.84
opencv-contrib-python==4.10.0.84
Empty file.
31 changes: 31 additions & 0 deletions dynamic-calibration/utils/arguments.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
import argparse


def initialize_argparser():
"""Initialize the argument parser for the script."""
parser = argparse.ArgumentParser(
formatter_class=argparse.ArgumentDefaultsHelpFormatter
)
parser.description = "This example showcases the capabinility of Dynamic Calibration on OAK devices. "

parser.add_argument(
"-d",
"--device",
help="Optional name, DeviceID or IP of the camera to connect to.",
required=False,
default=None,
type=str,
)

parser.add_argument(
"-fps",
"--fps_limit",
help="FPS limit for the model runtime.",
required=False,
default=10,
type=int,
)

args = parser.parse_args()

return parser, args
Loading
Loading