Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/stereo_filter_improvements' into…
Browse files Browse the repository at this point in the history
… HEAD
  • Loading branch information
SzabolcsGergely committed Oct 29, 2024
2 parents 6e262c1 + 53887f7 commit 7178d1a
Show file tree
Hide file tree
Showing 41 changed files with 232 additions and 14 deletions.
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
4 changes: 3 additions & 1 deletion 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 Expand Up @@ -68,7 +70,7 @@ def getFps(self):

out.setStreamName("out")

sync.setSyncThreshold(timedelta(seconds=(1 / FPS) * 0.5))
sync.setSyncThreshold(timedelta(seconds=0.5 / FPS))

# Linking
camRgb.isp.link(sync.inputs["rgb"])
Expand Down
4 changes: 3 additions & 1 deletion 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 Expand Up @@ -34,7 +36,7 @@

out.setStreamName("out")

sync.setSyncThreshold(timedelta(seconds=(1 / FPS) * 0.5))
sync.setSyncThreshold(timedelta(seconds=0.5 / FPS))

cfgIn.setStreamName("config")

Expand Down
4 changes: 3 additions & 1 deletion 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 Expand Up @@ -59,7 +61,7 @@ def getFps(self):

out.setStreamName("out")

sync.setSyncThreshold(timedelta(seconds=1/FPS * 0.5))
sync.setSyncThreshold(timedelta(seconds=0.5 / FPS))

cfgIn.setStreamName("config")

Expand Down
4 changes: 3 additions & 1 deletion 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 Expand Up @@ -50,7 +52,7 @@ def getFps(self):

out.setStreamName("out")

sync.setSyncThreshold(timedelta(seconds=(1 / FPS)))
sync.setSyncThreshold(timedelta(seconds=0.5 / FPS))

# Linking
camRgb.isp.link(sync.inputs["rgb"])
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.
31 changes: 31 additions & 0 deletions examples/Sync/sync_all_cameras.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#!/usr/bin/env python3

import cv2
import depthai as dai

with dai.Device() as device:
pipeline = dai.Pipeline()
cams = device.getConnectedCameraFeatures()
sync = pipeline.create(dai.node.Sync)
for cam in cams:
print(str(cam), str(cam.socket), cam.socket)
cam_node = pipeline.create(dai.node.Camera)
cam_node.setBoardSocket(cam.socket)
cam_node.isp.link(sync.inputs[str(cam.socket)])

xout = pipeline.create(dai.node.XLinkOut)
xout.setStreamName('sync')
sync.out.link(xout.input)

# Start pipeline
device.startPipeline(pipeline)
q = device.getOutputQueue('sync', maxSize=10, blocking=False)
while not device.isClosed():
msgs = q.get()
for (name, imgFrame) in msgs:
print(f'Cam {name}, seq {imgFrame.getSequenceNum()}, tiemstamp {imgFrame.getTimestamp()}')
cv2.imshow(name, imgFrame.getCvFrame())
print('----')

if cv2.waitKey(1) == ord('q'):
break
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
4 changes: 2 additions & 2 deletions examples/install_requirements.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,12 +55,12 @@ def hasWhitespace(string):
requireOpenCv = True

if requireOpenCv:
DEPENDENCIES.append('numpy')
DEPENDENCIES.append('numpy<3.0')
# 4.5.4.58 package is broken for python 3.9
if sys.version_info[0] == 3 and sys.version_info[1] == 9:
DEPENDENCIES.append('opencv-python!=4.5.4.58')
else:
DEPENDENCIES.append('opencv-python')
DEPENDENCIES.append('opencv-python<5.0')



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 @@ -507,6 +507,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
5 changes: 5 additions & 0 deletions src/pipeline/datatype/CameraControlBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,8 +243,13 @@ std::vector<const char *> camCtrlAttr;
.def("setEffectMode", &CameraControl::setEffectMode, py::arg("mode"), DOC(dai, CameraControl, setEffectMode))
.def("setControlMode", &CameraControl::setControlMode, py::arg("mode"), DOC(dai, CameraControl, setControlMode))
.def("setCaptureIntent", &CameraControl::setCaptureIntent, py::arg("mode"), DOC(dai, CameraControl, setCaptureIntent))
.def("setMisc", py::overload_cast<std::string, std::string>(&CameraControl::setMisc), py::arg("control"), py::arg("value"), DOC(dai, CameraControl, setMisc))
.def("setMisc", py::overload_cast<std::string, int>(&CameraControl::setMisc), py::arg("control"), py::arg("value"), DOC(dai, CameraControl, setMisc, 2))
.def("setMisc", py::overload_cast<std::string, float>(&CameraControl::setMisc), py::arg("control"), py::arg("value"), DOC(dai, CameraControl, setMisc, 3))
.def("clearMiscControls", &CameraControl::clearMiscControls, DOC(dai, CameraControl, clearMiscControls))
.def("set", &CameraControl::set, py::arg("config"), DOC(dai, CameraControl, set))
// getters
.def("getMiscControls", &CameraControl::getMiscControls, DOC(dai, CameraControl, getMiscControls))
.def("getCaptureStill", &CameraControl::getCaptureStill, DOC(dai, CameraControl, getCaptureStill))
.def("getExposureTime", &CameraControl::getExposureTime, DOC(dai, CameraControl, getExposureTime))
.def("getSensitivity", &CameraControl::getSensitivity, DOC(dai, CameraControl, getSensitivity))
Expand Down
13 changes: 12 additions & 1 deletion src/pipeline/datatype/StereoDepthConfigBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ void bind_stereodepthconfig(pybind11::module& m, void* pCallstack){
py::enum_<RawStereoDepthConfig::AlgorithmControl::DepthAlign> depthAlign(algorithmControl, "DepthAlign", DOC(dai, RawStereoDepthConfig, AlgorithmControl, DepthAlign));
py::enum_<RawStereoDepthConfig::AlgorithmControl::DepthUnit> depthUnit(algorithmControl, "DepthUnit", DOC(dai, RawStereoDepthConfig, AlgorithmControl, DepthUnit));
py::class_<RawStereoDepthConfig::PostProcessing> postProcessing(rawStereoDepthConfig, "PostProcessing", DOC(dai, RawStereoDepthConfig, PostProcessing));
py::enum_<RawStereoDepthConfig::PostProcessing::Filter> filter(postProcessing, "Filter", DOC(dai, RawStereoDepthConfig, PostProcessing, Filter));
py::class_<RawStereoDepthConfig::PostProcessing::SpatialFilter> spatialFilter(postProcessing, "SpatialFilter", DOC(dai, RawStereoDepthConfig, PostProcessing, SpatialFilter));
py::class_<RawStereoDepthConfig::PostProcessing::TemporalFilter> temporalFilter(postProcessing, "TemporalFilter", DOC(dai, RawStereoDepthConfig, PostProcessing, TemporalFilter));
py::enum_<RawStereoDepthConfig::PostProcessing::TemporalFilter::PersistencyMode> persistencyMode(temporalFilter, "PersistencyMode", DOC(dai, RawStereoDepthConfig, PostProcessing, TemporalFilter, PersistencyMode));
Expand Down Expand Up @@ -51,7 +52,15 @@ void bind_stereodepthconfig(pybind11::module& m, void* pCallstack){
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////

// Metadata / raw
filter
.value("DECIMATION", RawStereoDepthConfig::PostProcessing::Filter::DECIMATION, DOC(dai, RawStereoDepthConfig, PostProcessing, Filter, DECIMATION))
.value("SPECKLE", RawStereoDepthConfig::PostProcessing::Filter::SPECKLE, DOC(dai, RawStereoDepthConfig, PostProcessing, Filter, SPECKLE))
.value("MEDIAN", RawStereoDepthConfig::PostProcessing::Filter::MEDIAN, DOC(dai, RawStereoDepthConfig, PostProcessing, Filter, MEDIAN))
.value("TEMPORAL", RawStereoDepthConfig::PostProcessing::Filter::TEMPORAL, DOC(dai, RawStereoDepthConfig, PostProcessing, Filter, TEMPORAL))
.value("SPATIAL", RawStereoDepthConfig::PostProcessing::Filter::SPATIAL, DOC(dai, RawStereoDepthConfig, PostProcessing, Filter, SPATIAL))
.value("FILTER_COUNT", RawStereoDepthConfig::PostProcessing::Filter::FILTER_COUNT, DOC(dai, RawStereoDepthConfig, PostProcessing, Filter, FILTER_COUNT))
;

medianFilter
.value("MEDIAN_OFF", MedianFilter::MEDIAN_OFF)
.value("KERNEL_3x3", MedianFilter::KERNEL_3x3)
Expand Down Expand Up @@ -137,6 +146,7 @@ void bind_stereodepthconfig(pybind11::module& m, void* pCallstack){
.def(py::init<>())
.def_readwrite("enable", &RawStereoDepthConfig::PostProcessing::SpeckleFilter::enable, DOC(dai, RawStereoDepthConfig, PostProcessing, SpeckleFilter, enable))
.def_readwrite("speckleRange", &RawStereoDepthConfig::PostProcessing::SpeckleFilter::speckleRange, DOC(dai, RawStereoDepthConfig, PostProcessing, SpeckleFilter, speckleRange))
.def_readwrite("differenceThreshold", &RawStereoDepthConfig::PostProcessing::SpeckleFilter::differenceThreshold, DOC(dai, RawStereoDepthConfig, PostProcessing, SpeckleFilter, differenceThreshold))
;

decimationMode
Expand All @@ -153,6 +163,7 @@ void bind_stereodepthconfig(pybind11::module& m, void* pCallstack){

postProcessing
.def(py::init<>())
.def_readwrite("filteringOrder", &RawStereoDepthConfig::PostProcessing::filteringOrder, DOC(dai, RawStereoDepthConfig, PostProcessing, filteringOrder))
.def_readwrite("median", &RawStereoDepthConfig::PostProcessing::median, DOC(dai, RawStereoDepthConfig, PostProcessing, median))
.def_readwrite("bilateralSigmaValue", &RawStereoDepthConfig::PostProcessing::bilateralSigmaValue, DOC(dai, RawStereoDepthConfig, PostProcessing, bilateralSigmaValue))
.def_readwrite("spatialFilter", &RawStereoDepthConfig::PostProcessing::spatialFilter, DOC(dai, RawStereoDepthConfig, PostProcessing, spatialFilter))
Expand Down
1 change: 1 addition & 0 deletions src/pipeline/datatype/ToFConfigBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ void bind_tofconfig(pybind11::module& m, void* pCallstack){
.def_readwrite("median", &RawToFConfig::median, DOC(dai, RawToFConfig, median))
.def_readwrite("enablePhaseShuffleTemporalFilter", &RawToFConfig::enablePhaseShuffleTemporalFilter, DOC(dai, RawToFConfig, enablePhaseShuffleTemporalFilter))
.def_readwrite("enableBurstMode", &RawToFConfig::enableBurstMode, DOC(dai, RawToFConfig, enableBurstMode))
.def_readwrite("enableDistortionCorrection", &RawToFConfig::enableDistortionCorrection, DOC(dai, RawToFConfig, enableDistortionCorrection))
.def_readwrite("phaseUnwrappingLevel", &RawToFConfig::phaseUnwrappingLevel, DOC(dai, RawToFConfig, phaseUnwrappingLevel))
.def_readwrite("enableFPPNCorrection", &RawToFConfig::enableFPPNCorrection, DOC(dai, RawToFConfig, enableFPPNCorrection))
.def_readwrite("enableOpticalCorrection", &RawToFConfig::enableOpticalCorrection, DOC(dai, RawToFConfig, enableOpticalCorrection))
Expand Down
1 change: 1 addition & 0 deletions src/pipeline/node/ToFBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ void bind_tof(pybind11::module& m, void* pCallstack){
.def_readwrite("initialConfig", &ToFProperties::initialConfig, DOC(dai, ToFProperties, initialConfig))
.def_readwrite("numFramesPool", &ToFProperties::numFramesPool, DOC(dai, ToFProperties, numFramesPool))
.def_readwrite("numShaves", &ToFProperties::numShaves, DOC(dai, ToFProperties, numShaves))
.def_readwrite("warpHwIds", &ToFProperties::warpHwIds, DOC(dai, ToFProperties, warpHwIds))
;

// Node
Expand Down
Loading

0 comments on commit 7178d1a

Please sign in to comment.