Skip to content

Commit

Permalink
Merge pull request #937 from luxonis/release_v2.24.0.0
Browse files Browse the repository at this point in the history
Release v2.24.0.0
  • Loading branch information
moratom authored Dec 13, 2023
2 parents f5c5796 + bbf4048 commit 7b57b28
Show file tree
Hide file tree
Showing 26 changed files with 814 additions and 40 deletions.
8 changes: 6 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,8 @@ pybind11_add_module(${TARGET_NAME}
src/pipeline/node/WarpBindings.cpp
src/pipeline/node/UVCBindings.cpp
src/pipeline/node/ToFBindings.cpp
src/pipeline/node/SyncBindings.cpp
src/pipeline/node/MessageDemuxBindings.cpp

src/pipeline/datatype/ADatatypeBindings.cpp
src/pipeline/datatype/AprilTagConfigBindings.cpp
Expand All @@ -141,7 +143,9 @@ pybind11_add_module(${TARGET_NAME}
src/pipeline/datatype/ImageManipConfigBindings.cpp
src/pipeline/datatype/ImgDetectionsBindings.cpp
src/pipeline/datatype/ImgFrameBindings.cpp
src/pipeline/datatype/EncodedFrameBindings.cpp
src/pipeline/datatype/IMUDataBindings.cpp
src/pipeline/datatype/MessageGroupBindings.cpp
src/pipeline/datatype/NNDataBindings.cpp
src/pipeline/datatype/SpatialImgDetectionsBindings.cpp
src/pipeline/datatype/SpatialLocationCalculatorConfigBindings.cpp
Expand Down Expand Up @@ -173,8 +177,8 @@ endif()

# Add stubs (pyi) generation step after building bindings
execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" "from mypy import api" RESULT_VARIABLE error OUTPUT_QUIET ERROR_QUIET)
if(error)
message(WARNING "Mypy not available - stubs won't be generated or checked")
if(error OR CMAKE_CROSSCOMPILING)
message(WARNING "Mypy not available or cross compiling - stubs won't be generated or checked")
else()
get_target_property(bindings_directory ${TARGET_NAME} LIBRARY_OUTPUT_DIRECTORY)
if(NOT bindings_directory)
Expand Down
2 changes: 1 addition & 1 deletion depthai-core
Submodule depthai-core updated 43 files
+6 −1 CMakeLists.txt
+5 −0 README.md
+1 −1 cmake/Depthai/DepthaiDeviceSideConfig.cmake
+6 −6 cmake/Hunter/config.cmake
+6 −0 examples/CMakeLists.txt
+2 −2 examples/SpatialDetection/spatial_calculator_multi_roi.cpp
+63 −0 examples/Sync/demux_message_group.cpp
+68 −0 examples/Sync/depth_video_synced.cpp
+74 −0 examples/Sync/imu_video_synced.cpp
+56 −0 examples/Sync/sync_scripts.cpp
+4 −1 include/depthai/device/CalibrationHandler.hpp
+40 −4 include/depthai/device/DeviceBase.hpp
+3 −0 include/depthai/device/DeviceBootloader.hpp
+31 −1 include/depthai/pipeline/datatype/CameraControl.hpp
+144 −0 include/depthai/pipeline/datatype/EncodedFrame.hpp
+79 −0 include/depthai/pipeline/datatype/MessageGroup.hpp
+3 −0 include/depthai/pipeline/datatype/StreamMessageParser.hpp
+1 −0 include/depthai/pipeline/datatypes.hpp
+28 −0 include/depthai/pipeline/node/MessageDemux.hpp
+55 −0 include/depthai/pipeline/node/Sync.hpp
+6 −1 include/depthai/pipeline/node/VideoEncoder.hpp
+3 −1 include/depthai/pipeline/nodes.hpp
+1 −1 shared/depthai-shared
+1 −1 shared/depthai-shared.cmake
+33 −1 src/device/DataQueue.cpp
+225 −125 src/device/DeviceBase.cpp
+214 −208 src/device/DeviceBootloader.cpp
+20 −2 src/pipeline/datatype/CameraControl.cpp
+121 −0 src/pipeline/datatype/EncodedFrame.cpp
+77 −0 src/pipeline/datatype/MessageGroup.cpp
+24 −3 src/pipeline/datatype/StreamMessageParser.cpp
+16 −0 src/pipeline/node/MessageDemux.cpp
+31 −0 src/pipeline/node/Sync.cpp
+1 −1 src/pipeline/node/VideoEncoder.cpp
+38 −0 src/utility/Files.hpp
+292 −0 src/utility/H26xParsers.cpp
+16 −0 src/utility/H26xParsers.hpp
+9 −0 src/utility/Initialization.cpp
+27 −0 src/utility/Platform.cpp
+4 −3 src/utility/Platform.hpp
+4 −0 tests/CMakeLists.txt
+122 −0 tests/src/encoded_frame_test.cpp
+131 −0 tests/src/message_group_test.cpp
2 changes: 1 addition & 1 deletion docs/source/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
subprocess.check_call(['make', 'install'], cwd=tmpdir+'/libusb-1.0.24')
env['PATH'] = tmpdir+'/libusb/include:'+tmpdir+'/libusb/lib'+':'+env['PATH']

# Not needed anymore, part of pip install that carries the binary itself also
# Not needed since libclang usage in pip requirements (brings its own library)
# # libclang
# subprocess.check_call(['wget', 'https://artifacts.luxonis.com/artifactory/luxonis-depthai-data-local/misc/libclang-11_manylinux2014_x86_64.tar.xz'], cwd=tmpdir)
# subprocess.check_call(['mkdir', '-p', 'libclang'], cwd=tmpdir)
Expand Down
8 changes: 4 additions & 4 deletions examples/MonoCamera/mono_preview_alternate_pro.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@
script = pipeline.create(dai.node.Script)
script.setProcessor(dai.ProcessorType.LEON_CSS)
script.setScript("""
dotBright = 500 # Note: recommended to not exceed 765, for max duty cycle
floodBright = 200
dotBright = 0.8
floodBright = 0.1
LOGGING = False # Set `True` for latency/timings debugging
node.warn(f'IR drivers detected: {str(Device.getIrDrivers())}')
Expand All @@ -57,8 +57,8 @@
# Immediately reconfigure the IR driver.
# Note the logic is inverted, as it applies for next frame
Device.setIrLaserDotProjectorBrightness(0 if flagDot else dotBright)
Device.setIrFloodLightBrightness(floodBright if flagDot else 0)
Device.setIrLaserDotProjectorIntensity(0 if flagDot else dotBright)
Device.setIrFloodLightIntensity(floodBright if flagDot else 0)
if LOGGING: tIrSet = Clock.now()
# Wait for the actual frames (after MIPI capture and ISP proc is done)
Expand Down
17 changes: 13 additions & 4 deletions examples/StereoDepth/stereo_depth_from_host.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@
parser.add_argument("-e", "--evaluate", help="Evaluate the disparity calculation.", default=None)
parser.add_argument("-dumpdispcost", "--dumpdisparitycostvalues", action="store_true", help="Dumps the disparity cost values for each disparity range. 96 byte for each pixel.")
parser.add_argument("--download", action="store_true", help="Downloads the 2014 Middlebury dataset.")
parser.add_argument("--calibration", help="Path to calibration file", default=None)
parser.add_argument("--rectify", action="store_true", help="Enable rectified streams")
parser.add_argument("--swapLR", action="store_true", help="Swap left and right cameras.")
args = parser.parse_args()

if args.evaluate is not None and args.dataset is not None:
Expand Down Expand Up @@ -603,8 +606,12 @@ def __init__(self, config):
stereo.setRuntimeModeSwitch(True)

# Linking
monoLeft.out.link(stereo.left)
monoRight.out.link(stereo.right)
if(args.swapLR):
monoLeft.out.link(stereo.right)
monoRight.out.link(stereo.left)
else:
monoLeft.out.link(stereo.left)
monoRight.out.link(stereo.right)
xinStereoDepthConfig.out.link(stereo.inputConfig)
stereo.syncedLeft.link(xoutLeft.input)
stereo.syncedRight.link(xoutRight.input)
Expand All @@ -630,9 +637,11 @@ def __init__(self, config):
StereoConfigHandler.registerWindow("Stereo control panel")

# stereo.setPostProcessingHardwareResources(3, 3)

if(args.calibration):
calibrationHandler = dai.CalibrationHandler(args.calibration)
pipeline.setCalibrationData(calibrationHandler)
stereo.setInputResolution(width, height)
stereo.setRectification(False)
stereo.setRectification(args.rectify)
baseline = 75
fov = 71.86
focal = width / (2 * math.tan(fov / 2 / 180 * math.pi))
Expand Down
57 changes: 57 additions & 0 deletions examples/Sync/demux_message_group.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
import depthai as dai
import time
from datetime import timedelta

pipeline = dai.Pipeline()

script1 = pipeline.create(dai.node.Script)
script1.setScript("""
from time import sleep
while True:
sleep(1)
b = Buffer(512)
b.setData(bytes(4 * [i for i in range(0, 128)]))
b.setTimestamp(Clock.now())
node.io['out'].send(b)
""")

script2 = pipeline.create(dai.node.Script)
script2.setScript("""
from time import sleep
while True:
sleep(0.3)
b = Buffer(512)
b.setData(bytes(4 * [i for i in range(128, 256)]))
b.setTimestamp(Clock.now())
node.io['out'].send(b)
""")

sync = pipeline.create(dai.node.Sync)
sync.setSyncThresholdMs(timedelta(milliseconds=100))

demux = pipeline.create(dai.node.MessageDemux)

xout1 = pipeline.create(dai.node.XLinkOut)
xout1.setStreamName("xout1")
xout2 = pipeline.create(dai.node.XLinkOut)
xout2.setStreamName("xout2")

script1.outputs["out"].link(sync.inputs["s1"])
script2.outputs["out"].link(sync.inputs["s2"])
sync.out.link(demux.input)
demux.outputs["s1"].link(xout1.input)
demux.outputs["s2"].link(xout2.input)

with dai.Device(pipeline) as device:
print("Start")
q1 = device.getOutputQueue("xout1", maxSize=10, blocking=True)
q2 = device.getOutputQueue("xout2", maxSize=10, blocking=True)
while True:
bufS1 = q1.get()
bufS2 = q2.get()
print(f"Buffer 1 timestamp: {bufS1.getTimestamp()}")
print(f"Buffer 2 timestamp: {bufS2.getTimestamp()}")
print("----------")
time.sleep(0.2)
49 changes: 49 additions & 0 deletions examples/Sync/depth_video_synced.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
import depthai as dai
import numpy as np
import cv2
from datetime import timedelta

pipeline = dai.Pipeline()

monoLeft = pipeline.create(dai.node.MonoCamera)
monoRight = pipeline.create(dai.node.MonoCamera)
color = pipeline.create(dai.node.ColorCamera)
stereo = pipeline.create(dai.node.StereoDepth)
sync = pipeline.create(dai.node.Sync)

xoutGrp = pipeline.create(dai.node.XLinkOut)

xoutGrp.setStreamName("xout")

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

stereo.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_ACCURACY)

color.setCamera("color")

sync.setSyncThreshold(timedelta(milliseconds=50))

monoLeft.out.link(stereo.left)
monoRight.out.link(stereo.right)

stereo.disparity.link(sync.inputs["disparity"])
color.video.link(sync.inputs["video"])

sync.out.link(xoutGrp.input)

disparityMultiplier = 255.0 / stereo.initialConfig.getMaxDisparity()
with dai.Device(pipeline) as device:
queue = device.getOutputQueue("xout", 10, False)
while True:
msgGrp = queue.get()
for name, msg in msgGrp:
frame = msg.getCvFrame()
if name == "disparity":
frame = (frame * disparityMultiplier).astype(np.uint8)
frame = cv2.applyColorMap(frame, cv2.COLORMAP_JET)
cv2.imshow(name, frame)
if cv2.waitKey(1) == ord("q"):
break
59 changes: 59 additions & 0 deletions examples/Sync/imu_video_synced.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
import depthai as dai
import numpy as np
import cv2
from datetime import timedelta

device = dai.Device()

imuType = device.getConnectedIMU()
imuFirmwareVersion = device.getIMUFirmwareVersion()
print(f"IMU type: {imuType}, firmware version: {imuFirmwareVersion}")

if imuType != "BNO086":
print("Rotation vector output is supported only by BNO086!")
exit(0)

pipeline = dai.Pipeline()

color = pipeline.create(dai.node.ColorCamera)
imu = pipeline.create(dai.node.IMU)
sync = pipeline.create(dai.node.Sync)
xoutImu = pipeline.create(dai.node.XLinkOut)
xoutImu.setStreamName("imu")

xoutGrp = pipeline.create(dai.node.XLinkOut)
xoutGrp.setStreamName("xout")

color.setCamera("color")

imu.enableIMUSensor(dai.IMUSensor.ROTATION_VECTOR, 120)
imu.setBatchReportThreshold(1)
imu.setMaxBatchReports(10)

sync.setSyncThreshold(timedelta(milliseconds=10))
sync.setSyncAttempts(-1)

color.video.link(sync.inputs["video"])
imu.out.link(sync.inputs["imu"])

sync.out.link(xoutGrp.input)


with device:
device.startPipeline(pipeline)
groupQueue = device.getOutputQueue("xout", 3, True)
while True:
groupMessage = groupQueue.get()
imuMessage = groupMessage["imu"]
colorMessage = groupMessage["video"]
print()
print("Device timestamp imu: " + str(imuMessage.getTimestampDevice()))
print("Device timestamp video:" + str(colorMessage.getTimestampDevice()))
latestRotationVector = imuMessage.packets[-1].rotationVector
imuF = "{:.4f}"
print(f"Quaternion: i: {imuF.format(latestRotationVector.i)} j: {imuF.format(latestRotationVector.j)} "
f"k: {imuF.format(latestRotationVector.k)} real: {imuF.format(latestRotationVector.real)}")
print()
cv2.imshow("video", colorMessage.getCvFrame())
if cv2.waitKey(1) == ord("q"):
break
53 changes: 53 additions & 0 deletions examples/Sync/sync_scripts.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
import depthai as dai
import time
from datetime import timedelta

pipeline = dai.Pipeline()

script1 = pipeline.create(dai.node.Script)
script1.setScript("""
from time import sleep
while True:
sleep(1)
b = Buffer(512)
b.setData(bytes(4 * [i for i in range(0, 128)]))
b.setTimestamp(Clock.now())
node.io['out'].send(b)
""")

script2 = pipeline.create(dai.node.Script)
script2.setScript("""
from time import sleep
while True:
sleep(0.3)
b = Buffer(512)
b.setData(bytes(4 * [i for i in range(128, 256)]))
b.setTimestamp(Clock.now())
node.io['out'].send(b)
""")

sync = pipeline.create(dai.node.Sync)
sync.setSyncThreshold(timedelta(milliseconds=100))

xout = pipeline.create(dai.node.XLinkOut)
xout.setStreamName("xout")

sync.out.link(xout.input)

script1.outputs["out"].link(sync.inputs["s1"])
script2.outputs["out"].link(sync.inputs["s2"])

# script1.outputs["out"].link(xout.input)

with dai.Device(pipeline) as device:
print("Start")
q = device.getOutputQueue("xout", maxSize=10, blocking=True)
while True:
grp = q.get()
for name, msg in grp:
print(f"Received {name} with timestamp {msg.getTimestamp()}")
print(f"Time interval between messages: {grp.getIntervalNs() / 1e6}ms")
print("----------")
time.sleep(0.2)
69 changes: 69 additions & 0 deletions examples/VideoEncoder/rgb_encoding_encodedframe.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
#!/usr/bin/env python3

import depthai as dai

def frametype2str(ft):
if ft == dai.EncodedFrame.FrameType.I:
return "I"
elif ft == dai.EncodedFrame.FrameType.P:
return "P"
elif ft == dai.EncodedFrame.FrameType.B:
return "B"

def compress(ls):
curr = ls[0]
count = 1
res = []
for i in range(1, len(ls)):
if ls[i] == curr:
count += 1
else:
res.append((count, curr))
curr = ls[i]
count = 1
res.append((count, curr))
return res


# Create pipeline
pipeline = dai.Pipeline()

# Define sources and output
camRgb = pipeline.create(dai.node.ColorCamera)
videoEnc = pipeline.create(dai.node.VideoEncoder)
xout = pipeline.create(dai.node.XLinkOut)

xout.setStreamName('h265')

# Properties
camRgb.setBoardSocket(dai.CameraBoardSocket.CAM_A)
camRgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_4_K)
videoEnc.setDefaultProfilePreset(30, dai.VideoEncoderProperties.Profile.H265_MAIN)

# Linking
camRgb.video.link(videoEnc.input)
videoEnc.out.link(xout.input)

frametypes = []
# Connect to device and start pipeline
with dai.Device(pipeline) as device:

# Output queue will be used to get the encoded data from the output defined above
q = device.getOutputQueue(name="h265", maxSize=30, blocking=True)

# The .h265 file is a raw stream file (not playable yet)
with open('video.h265', 'wb') as videoFile:
print("Press Ctrl+C to stop encoding...")
try:
while True:
h265Packet = q.get() # Blocking call, will wait until a new data has arrived
frametypes.append(frametype2str(h265Packet.getFrameType()))
h265Packet.getData().tofile(videoFile) # Appends the packet data to the opened file
except KeyboardInterrupt:
# Keyboard interrupt (Ctrl + C) detected
pass

print("To view the encoded data, convert the stream file (.h265) into a video file (.mp4) using a command below:")
print("ffmpeg -framerate 30 -i video.h265 -c copy video.mp4")

print(",".join([f"{c}{f}" for c, f in compress(frametypes)]))
Loading

0 comments on commit 7b57b28

Please sign in to comment.