Skip to content

Commit

Permalink
Merge pull request #1017 from luxonis/dynamic_calib
Browse files Browse the repository at this point in the history
Add runtime stereo calib reconfig
  • Loading branch information
SzabolcsGergely authored Sep 26, 2024
2 parents 572492e + 6a3b60b commit a1d2c06
Show file tree
Hide file tree
Showing 33 changed files with 126 additions and 1 deletion.
2 changes: 2 additions & 0 deletions examples/Camera/camera_undistort.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import cv2

Expand Down
2 changes: 2 additions & 0 deletions examples/Camera/thermal_cam.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import cv2
import numpy as np
Expand Down
2 changes: 2 additions & 0 deletions examples/Cast/cast_blur.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import cv2
from pathlib import Path
Expand Down
2 changes: 2 additions & 0 deletions examples/Cast/cast_concat.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import numpy as np
import cv2
import depthai as dai
Expand Down
2 changes: 2 additions & 0 deletions examples/Cast/cast_diff.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import cv2
import depthai as dai
from pathlib import Path
Expand Down
2 changes: 2 additions & 0 deletions examples/ColorCamera/rgb_scene.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import cv2
import depthai as dai
from itertools import cycle
Expand Down
2 changes: 2 additions & 0 deletions examples/ColorCamera/rgb_undistort.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import cv2
import depthai as dai
import numpy as np
Expand Down
2 changes: 2 additions & 0 deletions examples/CrashReport/capture_diagnostic.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import zipfile
from json import dump, JSONEncoder
Expand Down
2 changes: 2 additions & 0 deletions examples/FeatureTracker/feature_motion_estimation.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import numpy as np
import cv2
from collections import deque
Expand Down
2 changes: 2 additions & 0 deletions examples/ImageAlign/depth_align.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import numpy as np
import cv2
import depthai as dai
Expand Down
2 changes: 2 additions & 0 deletions examples/ImageAlign/image_align.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import cv2
import depthai as dai
from datetime import timedelta
Expand Down
2 changes: 2 additions & 0 deletions examples/ImageAlign/thermal_align.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import cv2
import depthai as dai
import numpy as np
Expand Down
2 changes: 2 additions & 0 deletions examples/ImageAlign/tof_align.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import numpy as np
import cv2
import depthai as dai
Expand Down
2 changes: 2 additions & 0 deletions examples/NeuralNetwork/thermal_nnet.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import cv2
from pathlib import Path
Expand Down
2 changes: 2 additions & 0 deletions examples/PointCloud/pointcloud_control.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import numpy as np
import cv2
Expand Down
2 changes: 2 additions & 0 deletions examples/PointCloud/visualize_pointcloud.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
from time import sleep
import numpy as np
Expand Down
2 changes: 2 additions & 0 deletions examples/Script/script_emmc_access.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import cv2

Expand Down
Empty file modified examples/Script/script_read_calibration.py
100644 → 100755
Empty file.
Empty file modified examples/Script/script_uart.py
100644 → 100755
Empty file.
Empty file modified examples/StereoDepth/stereo_depth_custom_mesh.py
100644 → 100755
Empty file.
83 changes: 83 additions & 0 deletions examples/StereoDepth/stereo_runtime_calibration_update.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
#!/usr/bin/env python3

import cv2
import depthai as dai
import numpy as np

# Create pipeline
pipeline = dai.Pipeline()

# Define sources and outputs
monoLeft = pipeline.create(dai.node.MonoCamera)
monoRight = pipeline.create(dai.node.MonoCamera)
stereo = pipeline.create(dai.node.StereoDepth)
xout = pipeline.create(dai.node.XLinkOut)
xoutLeft = pipeline.create(dai.node.XLinkOut)

xout.setStreamName("disparity")
xoutLeft.setStreamName("left")

# Properties
monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoLeft.setCamera("left")
monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoRight.setCamera("right")

stereo.enableDistortionCorrection(True)

# Linking
monoLeft.out.link(stereo.left)
monoRight.out.link(stereo.right)
stereo.disparity.link(xout.input)
stereo.rectifiedLeft.link(xoutLeft.input)

cvColorMap = cv2.applyColorMap(np.arange(256, dtype=np.uint8), cv2.COLORMAP_JET)
cvColorMap[0] = [0, 0, 0]

# Connect to device and start pipeline
with dai.Device(pipeline) as device:

try:
calibration = device.readCalibration()
except:
print("Device is not calibrated!")
exit()

print("Press 'u' to update distortion coefficients with random values")

# Output queue will be used to get the disparity frames from the outputs defined above
q = device.getOutputQueue(name="disparity", maxSize=4, blocking=False)
qLeft = device.getOutputQueue(name="left", maxSize=4, blocking=False)

while True:
inDisparity = q.get() # blocking call, will wait until a new data has arrived
frame = inDisparity.getFrame()
# Normalization for better visualization
frame = (frame * (255 / stereo.initialConfig.getMaxDisparity())).astype(np.uint8)

cv2.imshow("disparity", frame)

frame = cv2.applyColorMap(frame, cvColorMap)
cv2.imshow("disparity_color", frame)

inLeft = qLeft.get()
frame = inLeft.getCvFrame()
cv2.imshow("rectified left", frame)

key = cv2.waitKey(1)
if key == ord('q'):
break
elif key == ord('u'):
randomDistortionCoeffs = np.random.rand(14)
calibration.setDistortionCoefficients(dai.CameraBoardSocket.LEFT, randomDistortionCoeffs)
try:
device.setCalibration(calibration)
except:
print("Failed to update calibration!")
try:
updatedCalib = device.getCalibration()
distortionCoeffs = updatedCalib.getDistortionCoefficients(dai.CameraBoardSocket.LEFT)
print("Updated distortion coefficients: ", distortionCoeffs)
except:
pass

Empty file modified examples/Sync/demux_message_group.py
100644 → 100755
Empty file.
Empty file modified examples/Sync/depth_video_synced.py
100644 → 100755
Empty file.
Empty file modified examples/Sync/imu_video_synced.py
100644 → 100755
Empty file.
Empty file modified examples/Sync/sync_scripts.py
100644 → 100755
Empty file.
Empty file modified examples/ToF/tof_depth.py
100644 → 100755
Empty file.
Empty file modified examples/UVC/uvc_disparity.py
100644 → 100755
Empty file.
Empty file modified examples/UVC/uvc_mono.py
100644 → 100755
Empty file.
2 changes: 2 additions & 0 deletions examples/device/device_all_boot_bootloader.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai

devices = dai.Device.getAllConnectedDevices()
Expand Down
2 changes: 2 additions & 0 deletions examples/device/device_boot_non_exclusive.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import time

Expand Down
2 changes: 2 additions & 0 deletions examples/mixed/collision_avoidance.py
100644 → 100755
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

import depthai as dai
import cv2
import numpy as np
Expand Down
2 changes: 2 additions & 0 deletions src/DeviceBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -504,6 +504,8 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){
.def("getProfilingData", [](DeviceBase& d) { py::gil_scoped_release release; return d.getProfilingData(); }, DOC(dai, DeviceBase, getProfilingData))
.def("readCalibration", [](DeviceBase& d) { py::gil_scoped_release release; return d.readCalibration(); }, DOC(dai, DeviceBase, readCalibration))
.def("flashCalibration", [](DeviceBase& d, CalibrationHandler calibrationDataHandler) { py::gil_scoped_release release; return d.flashCalibration(calibrationDataHandler); }, py::arg("calibrationDataHandler"), DOC(dai, DeviceBase, flashCalibration))
.def("setCalibration", [](DeviceBase& d, CalibrationHandler calibrationDataHandler) { py::gil_scoped_release release; return d.setCalibration(calibrationDataHandler); }, py::arg("calibrationDataHandler"), DOC(dai, DeviceBase, setCalibration))
.def("getCalibration", [](DeviceBase& d) { py::gil_scoped_release release; return d.getCalibration(); }, DOC(dai, DeviceBase, getCalibration))
.def("setXLinkChunkSize", [](DeviceBase& d, int s) { py::gil_scoped_release release; d.setXLinkChunkSize(s); }, py::arg("sizeBytes"), DOC(dai, DeviceBase, setXLinkChunkSize))
.def("getXLinkChunkSize", [](DeviceBase& d) { py::gil_scoped_release release; return d.getXLinkChunkSize(); }, DOC(dai, DeviceBase, getXLinkChunkSize))
.def("setIrLaserDotProjectorBrightness", [](DeviceBase& d, float mA, int mask) {
Expand Down

0 comments on commit a1d2c06

Please sign in to comment.