From a0fff5d309da9cf76babfc5ec57de8fc4cb7e906 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Mon, 29 Sep 2025 15:16:57 +0200 Subject: [PATCH 01/11] Add RPC wait for device Signed-off-by: stas.bucik --- src/device/DeviceBase.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index e78452ec1..bd5248c65 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1697,9 +1697,16 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { logCollection::logPipeline(schema, deviceInfo); this->pipelineSchema = schema; // Save the schema so it can be saved alongside the crashdump - // Build and start the pipeline bool success = false; std::string errorMsg; + + std::tie(success, errorMsg) = pimpl->rpcCall(std::chrono::seconds(60), "waitForDeviceReady").as>(); + + if (!success) { + throw std::runtime_error("Device not ready: " + errorMsg); + } + + // Build and start the pipeline std::tie(success, errorMsg) = pimpl->rpcCall("buildPipeline").as>(); if(success) { pimpl->rpcCall("startPipeline"); From 6085ae028b011f06d27e55bc87ab240442a60a69 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Tue, 23 Sep 2025 10:36:58 +0200 Subject: [PATCH 02/11] Add example script for fsync slave mode Signed-off-by: stas.bucik --- examples/cpp/Misc/CMakeLists.txt | 3 +- examples/cpp/Misc/MultiDevice/CMakeLists.txt | 7 + .../cpp/Misc/MultiDevice/multi_device.cpp | 175 +++++++++++++++++ .../python/Misc/MultiDevice/multi_device.py | 182 ++++++++++++++++++ 4 files changed, 366 insertions(+), 1 deletion(-) create mode 100644 examples/cpp/Misc/MultiDevice/CMakeLists.txt create mode 100644 examples/cpp/Misc/MultiDevice/multi_device.cpp create mode 100644 examples/python/Misc/MultiDevice/multi_device.py diff --git a/examples/cpp/Misc/CMakeLists.txt b/examples/cpp/Misc/CMakeLists.txt index 9e42fa359..4f73dd916 100644 --- a/examples/cpp/Misc/CMakeLists.txt +++ b/examples/cpp/Misc/CMakeLists.txt @@ -2,4 +2,5 @@ project(misc_examples) cmake_minimum_required(VERSION 3.10) add_subdirectory(AutoReconnect) -add_subdirectory(Projectors) \ No newline at end of file +add_subdirectory(Projectors) +add_subdirectory(MultiDevice) \ No newline at end of file diff --git a/examples/cpp/Misc/MultiDevice/CMakeLists.txt b/examples/cpp/Misc/MultiDevice/CMakeLists.txt new file mode 100644 index 000000000..2ce91b78f --- /dev/null +++ b/examples/cpp/Misc/MultiDevice/CMakeLists.txt @@ -0,0 +1,7 @@ +project(projectors_examples) +cmake_minimum_required(VERSION 3.10) + +## function: dai_add_example(example_name example_src enable_test use_pcl) +## function: dai_set_example_test_labels(example_name ...) + +dai_add_example(multi_device multi_device.cpp OFF OFF) \ No newline at end of file diff --git a/examples/cpp/Misc/MultiDevice/multi_device.cpp b/examples/cpp/Misc/MultiDevice/multi_device.cpp new file mode 100644 index 000000000..d1e79155e --- /dev/null +++ b/examples/cpp/Misc/MultiDevice/multi_device.cpp @@ -0,0 +1,175 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "depthai/capabilities/ImgFrameCapability.hpp" +#include "depthai/common/CameraBoardSocket.hpp" +#include "depthai/common/CameraExposureOffset.hpp" +#include "depthai/depthai.hpp" +#include "depthai/pipeline/MessageQueue.hpp" +#include "depthai/pipeline/Node.hpp" +#include "depthai/pipeline/datatype/ImgFrame.hpp" +#include "depthai/pipeline/node/Camera.hpp" +#include "depthai/xlink/XLinkConnection.hpp" + +class FPSCounter { + public: + std::vector> frameTimes; + + void tick() { + auto now = std::chrono::steady_clock::now(); + frameTimes.push_back(now); + if (frameTimes.size() > 100) { + frameTimes.erase(frameTimes.begin(), frameTimes.begin() + (frameTimes.size() - 100)); + } + } + + float getFps() { + if (frameTimes.size() <= 1) { + return 0.0f; + } + // Calculate the FPS + return float(frameTimes.size() - 1) * 1e6 / std::chrono::duration_cast(frameTimes.back() - frameTimes.front()).count(); + } +}; + + +int main(int argc, char** argv) { + + if (argc < 4) { + std::cout << "Usage: " << argv[0] << " [device_ip_3] ..." << std::endl; + std::exit(0); + } + + float TARGET_FPS = std::stof(argv[1]); + + std::vector DEVICE_INFOS; + for (int i = 2; i < argc; i++) { + DEVICE_INFOS.emplace_back(std::string(argv[i])); + } + + std::vector> queues; + std::vector pipelines; + std::vector device_ids; + + for (auto deviceInfo : DEVICE_INFOS) + { + auto pipeline = dai::Pipeline(std::make_shared(deviceInfo)); + auto device = pipeline.getDefaultDevice(); + + std::cout << "=== Connected to " << deviceInfo.getDeviceId() << std::endl; + std::cout << " Device ID: " << device->getDeviceId() << std::endl; + std::cout << " Num of cameras: " << device->getConnectedCameras().size() << std::endl; + + // auto socket = device->getConnectedCameras()[0]; + auto socket = device->getConnectedCameras()[1]; + + auto cam = pipeline.create()->build(socket, std::nullopt, TARGET_FPS); + auto out_q = cam->requestOutput(std::make_pair(640, 480), dai::ImgFrame::Type::NV12, dai::ImgResizeMode::STRETCH)->createOutputQueue(); + + pipeline.start(); + pipelines.push_back(pipeline); + queues.push_back(out_q); + device_ids.push_back(deviceInfo.getXLinkDeviceDesc().name); + } + + std::map> latest_frames; + std::vector receivedFrames; + std::vector fpsCounters(queues.size()); + + for(auto q : queues) { + receivedFrames.push_back(false); + } + + int counter = 0; + + while (true) { + for (int i = 0; i < queues.size(); i++) { + auto q = queues[i]; + while (q->has()) { + latest_frames.emplace(std::make_pair(i,std::dynamic_pointer_cast(q->get()))); + if (!receivedFrames[i]) { + std::cout << "=== Received frame from " << device_ids[i] << std::endl; + receivedFrames[i] = true; + } + fpsCounters[i].tick(); + } + } + + if (latest_frames.size() == queues.size()) { + std::vector> ts_values; + for (auto pair : latest_frames) { + auto f = pair.second; + ts_values.push_back(f->getTimestamp(dai::CameraExposureOffset::END)); + } + + if (counter % 100000 == 0) { + auto diff = *std::max_element(ts_values.begin(), ts_values.end()) - *std::min_element(ts_values.begin(), ts_values.end()); + std::cout << 1e-6 * float(std::chrono::duration_cast(diff).count()) << std::endl; + } + + if (true) { + // std::vector imgs; + cv::Mat imgs; + for (int i = 0; i < queues.size(); i++) { + auto msg = latest_frames[i]; + auto fps = fpsCounters[i].getFps(); + auto frame = msg->getCvFrame(); + + cv::putText(frame, + device_ids[i] + " | Timestamp: " + std::to_string(ts_values[i].time_since_epoch().count()) + " | FPS: " + std::to_string(fps).substr(0, 5), + {20, 40}, + cv::FONT_HERSHEY_SIMPLEX, + 0.6, + {255, 0, 50}, + 2, + cv::LINE_AA); + + if (i == 0) { + imgs = frame; + } else { + cv::hconcat(frame, imgs, imgs); + } + } + + std::string sync_status = "out of sync"; + if (abs(std::chrono::duration_cast( + *std::max_element(ts_values.begin(), ts_values.end()) - + *std::min_element(ts_values.begin(), ts_values.end()) + ).count()) < 1e3) { + sync_status = "in sync"; + } + auto delta = *std::max_element(ts_values.begin(), ts_values.end()) - *std::min_element(ts_values.begin(), ts_values.end()); + cv::Scalar color = (sync_status == "in sync") ? cv::Scalar(0, 255, 0) : cv::Scalar(0, 0, 255); + + cv::putText(imgs, + sync_status + " | delta = " + std::to_string(1e-3 * float(std::chrono::duration_cast(delta).count())).substr(0, 5) + " ms", + {20, 80}, + cv::FONT_HERSHEY_SIMPLEX, + 0.7, + color, + 2, + cv::LINE_AA); + + cv::imshow("synced_view", imgs); + + latest_frames.clear(); + } + } + + if (cv::waitKey(1) == 'q') { + break; + } + } + + return 0; +} \ No newline at end of file diff --git a/examples/python/Misc/MultiDevice/multi_device.py b/examples/python/Misc/MultiDevice/multi_device.py new file mode 100644 index 000000000..c7a2b834c --- /dev/null +++ b/examples/python/Misc/MultiDevice/multi_device.py @@ -0,0 +1,182 @@ +#!/usr/bin/env python3 + +""" +Minimal changes to original script: + * Adds simple timestamp-based synchronisation across multiple devices. + * Presents frames side‑by‑side when they are within 1 / FPS seconds. + * Keeps v3 API usage and overall code structure intact. +""" + +import contextlib +import datetime + +import cv2 +import depthai as dai +import time +import math + +import argparse +# --------------------------------------------------------------------------- +# Configuration +# --------------------------------------------------------------------------- +SET_MANUAL_EXPOSURE = False # Set to True to use manual exposure settings +# --------------------------------------------------------------------------- +# Helpers +# --------------------------------------------------------------------------- +class FPSCounter: + def __init__(self): + self.frameTimes = [] + + def tick(self): + now = time.time() + self.frameTimes.append(now) + self.frameTimes = self.frameTimes[-100:] + + def getFps(self): + if len(self.frameTimes) <= 1: + return 0 + # Calculate the FPS + return (len(self.frameTimes) - 1) / (self.frameTimes[-1] - self.frameTimes[0]) + + +def format_time(td: datetime.timedelta) -> str: + hours, remainder_seconds = divmod(td.seconds, 3600) + minutes, seconds = divmod(remainder_seconds, 60) + milliseconds, microseconds_remainder = divmod(td.microseconds, 1000) + days_prefix = f"{td.days} day{'s' if td.days != 1 else ''}, " if td.days else "" + return ( + f"{days_prefix}{hours:02d}:{minutes:02d}:{seconds:02d}." + f"{milliseconds:03d}.{microseconds_remainder:03d}" + ) + + +# --------------------------------------------------------------------------- +# Pipeline creation (unchanged API – only uses TARGET_FPS constant) +# --------------------------------------------------------------------------- +def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.CameraBoardSocket.CAM_A): + camRgb = ( + pipeline.create(dai.node.Camera) + .build(socket, sensorFps=TARGET_FPS) + ) + output = ( + camRgb.requestOutput( + (640, 480), dai.ImgFrame.Type.NV12, dai.ImgResizeMode.STRETCH + ).createOutputQueue(blocking=False) + ) + if SET_MANUAL_EXPOSURE: + camRgb.initialControl.setManualExposure(1000, 100) + return pipeline, output + + +parser = argparse.ArgumentParser(add_help=False) +parser.add_argument("-d", "--devices", default=[], nargs="+", help="Device IPs, first is master, others are slaves") +parser.add_argument("-f", "--fps", type=float, default=30.0, help="Target FPS") +args = parser.parse_args() +DEVICE_INFOS = [dai.DeviceInfo(ip) for ip in args.devices] #The master camera needs to be first here +assert len(DEVICE_INFOS) > 1, "At least two devices are required for this example." + +TARGET_FPS = args.fps # Must match sensorFps in createPipeline() +SYNC_THRESHOLD_SEC = 1.0 / (2 * TARGET_FPS) # Max drift to accept as "in sync" +# --------------------------------------------------------------------------- +# Main +# --------------------------------------------------------------------------- +with contextlib.ExitStack() as stack: + # deviceInfos = dai.Device.getAllAvailableDevices() + # print("=== Found devices: ", deviceInfos) + + queues = [] + pipelines = [] + device_ids = [] + + for idx, deviceInfo in enumerate(DEVICE_INFOS): + pipeline = stack.enter_context(dai.Pipeline(dai.Device(deviceInfo))) + device = pipeline.getDefaultDevice() + + print("=== Connected to", deviceInfo.getDeviceId()) + print(" Device ID:", device.getDeviceId()) + print(" Num of cameras:", len(device.getConnectedCameras())) + + # for c in device.getConnectedCameras(): + # print(f" {c}") + + # socket = device.getConnectedCameras()[0] + socket = device.getConnectedCameras()[1] + pipeline, out_q = createPipeline(pipeline, socket) + print(type(out_q)) + pipeline.start() + + pipelines.append(pipeline) + queues.append(out_q) + device_ids.append(deviceInfo.getXLinkDeviceDesc().name) + # if (idx == 0): + # time.sleep(12) + + # Buffer for latest frames; key = queue index + latest_frames = {} + fpsCounters = [FPSCounter() for _ in queues] + receivedFrames = [False for _ in queues] + counter = 0 + while True: + # ------------------------------------------------------------------- + # Collect the newest frame from each queue (non‑blocking) + # ------------------------------------------------------------------- + for idx, q in enumerate(queues): + while q.has(): + latest_frames[idx] = q.get() + if not receivedFrames[idx]: + print("=== Received frame from", device_ids[idx]) + receivedFrames[idx] = True + fpsCounters[idx].tick() + + # ------------------------------------------------------------------- + # Synchronise: we need at least one frame from every camera and their + # timestamps must align within SYNC_THRESHOLD_SEC. + # ------------------------------------------------------------------- + if len(latest_frames) == len(queues): + ts_values = [f.getTimestamp(dai.CameraExposureOffset.END).total_seconds() for f in latest_frames.values()] + if (counter % 100000 == 0): + print(max(ts_values) - min(ts_values)) + counter += 1 + # if max(ts_values) - min(ts_values) <= SYNC_THRESHOLD_SEC: + # TIMESTAMPS ARE NOT ACCURATE, VERIFIED WITH PIXEL RUNNER + if True: + # Build composite image side‑by‑side + imgs = [] + for i in range(len(queues)): + msg = latest_frames[i] + frame = msg.getCvFrame() + fps = fpsCounters[i].getFps() + cv2.putText( + frame, + f"{device_ids[i]} | Timestamp: {ts_values[i]} | FPS:{fps:.2f}", + (20, 40), + cv2.FONT_HERSHEY_SIMPLEX, + 0.6, + (255, 0, 50), + 2, + cv2.LINE_AA, + ) + imgs.append(frame) + + sync_status = "in sync" if abs(max(ts_values) - min(ts_values)) < 0.001 else "out of sync" + delta = max(ts_values) - min(ts_values) + color = (0, 255, 0) if sync_status == "in sync" else (0, 0, 255) + + cv2.putText( + imgs[0], + f"{sync_status} | delta = {delta*1e3:.3f} ms", + (20, 80), + cv2.FONT_HERSHEY_SIMPLEX, + 0.7, + color, + 2, + cv2.LINE_AA, + ) + + cv2.imshow("synced_view", cv2.hconcat(imgs)) + latest_frames.clear() # Wait for next batch + + if cv2.waitKey(1) & 0xFF == ord("q"): + break + +cv2.destroyAllWindows() From b09ef6fc7ccc7277941a17060192ed50b9b89a4e Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Wed, 1 Oct 2025 13:55:46 +0200 Subject: [PATCH 03/11] Add M8 Fsync role switching Signed-off-by: stas.bucik --- bindings/python/src/DeviceBindings.cpp | 17 ++++++++ .../python/src/pipeline/CommonBindings.cpp | 8 ++++ include/depthai/common/M8FsyncRoles.hpp | 40 +++++++++++++++++++ include/depthai/device/DeviceBase.hpp | 14 +++++++ src/device/DeviceBase.cpp | 8 ++++ 5 files changed, 87 insertions(+) create mode 100644 include/depthai/common/M8FsyncRoles.hpp diff --git a/bindings/python/src/DeviceBindings.cpp b/bindings/python/src/DeviceBindings.cpp index 02ac33560..b168038c5 100644 --- a/bindings/python/src/DeviceBindings.cpp +++ b/bindings/python/src/DeviceBindings.cpp @@ -837,6 +837,23 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack) { }, py::arg("enable"), DOC(dai, DeviceBase, setTimesync, 2)) + .def( + "setM8FsyncRole", + [](DeviceBase& d, M8FsyncRole role) { + py::gil_scoped_release release; + return d.setM8FsyncRole(role); + }, + py::arg("role"), + DOC(dai, DeviceBase, setM8FsyncRole) + ) + .def( + "getM8FsyncRole", + [](DeviceBase& d) { + py::gil_scoped_release release; + return d.getM8FsyncRole(); + }, + DOC(dai, DeviceBase, getM8FsyncRole) + ) .def( "getDeviceName", [](DeviceBase& d) { diff --git a/bindings/python/src/pipeline/CommonBindings.cpp b/bindings/python/src/pipeline/CommonBindings.cpp index f2352cb62..16bda83b2 100644 --- a/bindings/python/src/pipeline/CommonBindings.cpp +++ b/bindings/python/src/pipeline/CommonBindings.cpp @@ -5,6 +5,7 @@ // depthai/ #include "depthai/common/CameraBoardSocket.hpp" +#include "depthai/common/M8FsyncRoles.hpp" #include "depthai/common/CameraFeatures.hpp" #include "depthai/common/CameraImageOrientation.hpp" #include "depthai/common/CameraSensorType.hpp" @@ -50,6 +51,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack) { py::class_ quaterniond(m, "Quaterniond", DOC(dai, Quaterniond)); py::class_ size2f(m, "Size2f", DOC(dai, Size2f)); py::enum_ cameraBoardSocket(m, "CameraBoardSocket", DOC(dai, CameraBoardSocket)); + py::enum_ m8FsyncRole(m, "M8FsyncRole", DOC(dai, M8FsyncRole)); py::enum_ connectionInterface(m, "connectionInterface", DOC(dai, ConnectionInterface)); py::enum_ cameraSensorType(m, "CameraSensorType", DOC(dai, CameraSensorType)); py::enum_ cameraImageOrientation(m, "CameraImageOrientation", DOC(dai, CameraImageOrientation)); @@ -221,6 +223,12 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack) { }); HEDLEY_DIAGNOSTIC_POP + // M8FsyncRole enum bindings + m8FsyncRole.value("AUTO_DETECT", M8FsyncRole::AUTO_DETECT) + .value("MASTER_WITHOUT_OUTPUT", M8FsyncRole::MASTER_WITHOUT_OUTPUT) + .value("MASTER_WITH_OUTPUT", M8FsyncRole::MASTER_WITH_OUTPUT) + .value("SLAVE", M8FsyncRole::SLAVE); + // CameraSensorType enum bindings cameraSensorType.value("COLOR", CameraSensorType::COLOR) .value("MONO", CameraSensorType::MONO) diff --git a/include/depthai/common/M8FsyncRoles.hpp b/include/depthai/common/M8FsyncRoles.hpp new file mode 100644 index 000000000..601e7929d --- /dev/null +++ b/include/depthai/common/M8FsyncRoles.hpp @@ -0,0 +1,40 @@ +#pragma once +#include +#include +#include + +namespace dai { +/** + * Which Fsymc role the device will have. + * + * AUTO_DETECT denotes that the decision will be made by device. + * It will choose between MASTER_WITH_OUTPUT and SLAVE. + */ +enum class M8FsyncRole : int32_t { + AUTO_DETECT = -1, + MASTER_WITHOUT_OUTPUT, + MASTER_WITH_OUTPUT, + SLAVE, +}; + +inline std::string toString(M8FsyncRole role) { + switch(role) { + case M8FsyncRole::AUTO_DETECT: + return "AUTO DETECT"; + case M8FsyncRole::MASTER_WITHOUT_OUTPUT: + return "MASTER, NO OUTPUT"; + case M8FsyncRole::MASTER_WITH_OUTPUT: + return "MASTER, WITH OUTPUT"; + case M8FsyncRole::SLAVE: + return "SLAVE"; + default: + return "UNKNOWN"; + } +} + +} // namespace dai + +// Global namespace +inline std::ostream& operator<<(std::ostream& out, const dai::M8FsyncRole& socket) { + return out << dai::toString(socket); +} diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 7aeb5615b..80efb2f1d 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -17,6 +17,7 @@ // project #include "depthai/common/CameraBoardSocket.hpp" #include "depthai/common/CameraFeatures.hpp" +#include "depthai/common/M8FsyncRoles.hpp" #include "depthai/common/UsbSpeed.hpp" #include "depthai/device/CalibrationHandler.hpp" #include "depthai/device/DeviceGate.hpp" @@ -797,6 +798,19 @@ class DeviceBase { */ void setMaxReconnectionAttempts(int maxAttempts, std::function callBack = nullptr); + /** + * Sets M8 Fsync role for the device + * @param role M8 Fsync role to be set, AUTO_DETECT by default + * @returns Tuple of bool and string. Bool specifies if role was set without failures. String is the error message describing the failure reason. + */ + std::tuple setM8FsyncRole(M8FsyncRole role = M8FsyncRole::AUTO_DETECT); + + /** + * Gets M8 Fsync role for the device + * @returns Gets M8 Fsync role + */ + M8FsyncRole getM8FsyncRole(); + protected: std::shared_ptr connection; diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index bd5248c65..5e9d054ac 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1228,6 +1228,14 @@ void DeviceBase::crashDevice() { } } +std::tuple DeviceBase::setM8FsyncRole(M8FsyncRole role) { + return pimpl->rpcClient->call("setM8FsyncRole", role); +} + +M8FsyncRole DeviceBase::getM8FsyncRole() { + return pimpl->rpcClient->call("getM8FsyncRole"); +} + dai::Version DeviceBase::getIMUFirmwareVersion() { isClosed(); std::string versionStr = pimpl->rpcCall("getIMUFirmwareVersion").as(); From 5089a873bad26007292e955bf86e464c3ee3d969 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Thu, 2 Oct 2025 09:49:47 +0200 Subject: [PATCH 04/11] Update examples Signed-off-by: stas.bucik --- .../cpp/Misc/MultiDevice/multi_device.cpp | 121 ++++++++++-------- .../python/Misc/MultiDevice/multi_device.py | 107 ++++++++-------- 2 files changed, 126 insertions(+), 102 deletions(-) diff --git a/examples/cpp/Misc/MultiDevice/multi_device.cpp b/examples/cpp/Misc/MultiDevice/multi_device.cpp index d1e79155e..cce9540b1 100644 --- a/examples/cpp/Misc/MultiDevice/multi_device.cpp +++ b/examples/cpp/Misc/MultiDevice/multi_device.cpp @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include @@ -14,6 +15,7 @@ #include "depthai/capabilities/ImgFrameCapability.hpp" #include "depthai/common/CameraBoardSocket.hpp" #include "depthai/common/CameraExposureOffset.hpp" +#include "depthai/common/M8FsyncRoles.hpp" #include "depthai/depthai.hpp" #include "depthai/pipeline/MessageQueue.hpp" #include "depthai/pipeline/Node.hpp" @@ -58,7 +60,8 @@ int main(int argc, char** argv) { } std::vector> queues; - std::vector pipelines; + std::vector master_pipelines; + std::vector slave_pipelines; std::vector device_ids; for (auto deviceInfo : DEVICE_INFOS) @@ -76,12 +79,36 @@ int main(int argc, char** argv) { auto cam = pipeline.create()->build(socket, std::nullopt, TARGET_FPS); auto out_q = cam->requestOutput(std::make_pair(640, 480), dai::ImgFrame::Type::NV12, dai::ImgResizeMode::STRETCH)->createOutputQueue(); - pipeline.start(); - pipelines.push_back(pipeline); + auto role = device->getM8FsyncRole(); + + if (role == dai::M8FsyncRole::MASTER_WITH_OUTPUT) { + master_pipelines.push_back(pipeline); + } else if (role == dai::M8FsyncRole::SLAVE) { + slave_pipelines.push_back(pipeline); + } else { + throw std::runtime_error("Don't know how to handle role " + dai::toString(role)); + } + queues.push_back(out_q); device_ids.push_back(deviceInfo.getXLinkDeviceDesc().name); } + if (master_pipelines.size() > 1) { + throw std::runtime_error("Multiple masters detected!"); + } + if (master_pipelines.size() == 0) { + throw std::runtime_error("No master detected!"); + } + if (slave_pipelines.size() < 1) { + throw std::runtime_error("No slaves detected!"); + } + for (auto p : master_pipelines) { + p.start(); + } + for (auto p : slave_pipelines) { + p.start(); + } + std::map> latest_frames; std::vector receivedFrames; std::vector fpsCounters(queues.size()); @@ -90,8 +117,6 @@ int main(int argc, char** argv) { receivedFrames.push_back(false); } - int counter = 0; - while (true) { for (int i = 0; i < queues.size(); i++) { auto q = queues[i]; @@ -111,59 +136,51 @@ int main(int argc, char** argv) { auto f = pair.second; ts_values.push_back(f->getTimestamp(dai::CameraExposureOffset::END)); } - - if (counter % 100000 == 0) { - auto diff = *std::max_element(ts_values.begin(), ts_values.end()) - *std::min_element(ts_values.begin(), ts_values.end()); - std::cout << 1e-6 * float(std::chrono::duration_cast(diff).count()) << std::endl; - } - - if (true) { - // std::vector imgs; - cv::Mat imgs; - for (int i = 0; i < queues.size(); i++) { - auto msg = latest_frames[i]; - auto fps = fpsCounters[i].getFps(); - auto frame = msg->getCvFrame(); - - cv::putText(frame, - device_ids[i] + " | Timestamp: " + std::to_string(ts_values[i].time_since_epoch().count()) + " | FPS: " + std::to_string(fps).substr(0, 5), - {20, 40}, - cv::FONT_HERSHEY_SIMPLEX, - 0.6, - {255, 0, 50}, - 2, - cv::LINE_AA); - - if (i == 0) { - imgs = frame; - } else { - cv::hconcat(frame, imgs, imgs); - } - } - - std::string sync_status = "out of sync"; - if (abs(std::chrono::duration_cast( - *std::max_element(ts_values.begin(), ts_values.end()) - - *std::min_element(ts_values.begin(), ts_values.end()) - ).count()) < 1e3) { - sync_status = "in sync"; - } - auto delta = *std::max_element(ts_values.begin(), ts_values.end()) - *std::min_element(ts_values.begin(), ts_values.end()); - cv::Scalar color = (sync_status == "in sync") ? cv::Scalar(0, 255, 0) : cv::Scalar(0, 0, 255); - - cv::putText(imgs, - sync_status + " | delta = " + std::to_string(1e-3 * float(std::chrono::duration_cast(delta).count())).substr(0, 5) + " ms", - {20, 80}, + + cv::Mat imgs; + for (int i = 0; i < queues.size(); i++) { + auto msg = latest_frames[i]; + auto fps = fpsCounters[i].getFps(); + auto frame = msg->getCvFrame(); + + cv::putText(frame, + device_ids[i] + " | Timestamp: " + std::to_string(ts_values[i].time_since_epoch().count()) + " | FPS: " + std::to_string(fps).substr(0, 5), + {20, 40}, cv::FONT_HERSHEY_SIMPLEX, - 0.7, - color, + 0.6, + {255, 0, 50}, 2, cv::LINE_AA); - cv::imshow("synced_view", imgs); + if (i == 0) { + imgs = frame; + } else { + cv::hconcat(frame, imgs, imgs); + } + } - latest_frames.clear(); + std::string sync_status = "out of sync"; + if (abs(std::chrono::duration_cast( + *std::max_element(ts_values.begin(), ts_values.end()) - + *std::min_element(ts_values.begin(), ts_values.end()) + ).count()) < 1e3) { + sync_status = "in sync"; } + auto delta = *std::max_element(ts_values.begin(), ts_values.end()) - *std::min_element(ts_values.begin(), ts_values.end()); + cv::Scalar color = (sync_status == "in sync") ? cv::Scalar(0, 255, 0) : cv::Scalar(0, 0, 255); + + cv::putText(imgs, + sync_status + " | delta = " + std::to_string(1e-3 * float(std::chrono::duration_cast(delta).count())).substr(0, 5) + " ms", + {20, 80}, + cv::FONT_HERSHEY_SIMPLEX, + 0.7, + color, + 2, + cv::LINE_AA); + + cv::imshow("synced_view", imgs); + + latest_frames.clear(); } if (cv::waitKey(1) == 'q') { diff --git a/examples/python/Misc/MultiDevice/multi_device.py b/examples/python/Misc/MultiDevice/multi_device.py index c7a2b834c..a0fdaaac4 100644 --- a/examples/python/Misc/MultiDevice/multi_device.py +++ b/examples/python/Misc/MultiDevice/multi_device.py @@ -69,7 +69,7 @@ def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.C parser = argparse.ArgumentParser(add_help=False) -parser.add_argument("-d", "--devices", default=[], nargs="+", help="Device IPs, first is master, others are slaves") +parser.add_argument("-d", "--devices", default=[], nargs="+", help="Device IPs") parser.add_argument("-f", "--fps", type=float, default=30.0, help="Target FPS") args = parser.parse_args() DEVICE_INFOS = [dai.DeviceInfo(ip) for ip in args.devices] #The master camera needs to be first here @@ -81,11 +81,10 @@ def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.C # Main # --------------------------------------------------------------------------- with contextlib.ExitStack() as stack: - # deviceInfos = dai.Device.getAllAvailableDevices() - # print("=== Found devices: ", deviceInfos) queues = [] - pipelines = [] + slave_pipelines = [] + master_pipelines = [] device_ids = [] for idx, deviceInfo in enumerate(DEVICE_INFOS): @@ -96,26 +95,40 @@ def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.C print(" Device ID:", device.getDeviceId()) print(" Num of cameras:", len(device.getConnectedCameras())) - # for c in device.getConnectedCameras(): - # print(f" {c}") - # socket = device.getConnectedCameras()[0] socket = device.getConnectedCameras()[1] pipeline, out_q = createPipeline(pipeline, socket) - print(type(out_q)) - pipeline.start() - - pipelines.append(pipeline) + role = device.getM8FsyncRole() + if (role == dai.M8FsyncRole.MASTER_WITH_OUTPUT): + master_pipelines.append(pipeline) + elif (role == dai.M8FsyncRole.SLAVE): + slave_pipelines.append(pipeline) + else: + raise RuntimeError(f"Don't know how to handle role {role}") + queues.append(out_q) device_ids.append(deviceInfo.getXLinkDeviceDesc().name) - # if (idx == 0): - # time.sleep(12) + + if (len(master_pipelines) > 1): + raise RuntimeError("Multiple masters detected!") + + if (len(master_pipelines) == 0): + raise RuntimeError("No master detected!") + + if (len(slave_pipelines) < 1): + raise RuntimeError("No slaves detected!") + + for p in master_pipelines: + p.start() + + for p in slave_pipelines: + p.start() + # Buffer for latest frames; key = queue index latest_frames = {} fpsCounters = [FPSCounter() for _ in queues] receivedFrames = [False for _ in queues] - counter = 0 while True: # ------------------------------------------------------------------- # Collect the newest frame from each queue (non‑blocking) @@ -134,47 +147,41 @@ def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.C # ------------------------------------------------------------------- if len(latest_frames) == len(queues): ts_values = [f.getTimestamp(dai.CameraExposureOffset.END).total_seconds() for f in latest_frames.values()] - if (counter % 100000 == 0): - print(max(ts_values) - min(ts_values)) - counter += 1 - # if max(ts_values) - min(ts_values) <= SYNC_THRESHOLD_SEC: - # TIMESTAMPS ARE NOT ACCURATE, VERIFIED WITH PIXEL RUNNER - if True: - # Build composite image side‑by‑side - imgs = [] - for i in range(len(queues)): - msg = latest_frames[i] - frame = msg.getCvFrame() - fps = fpsCounters[i].getFps() - cv2.putText( - frame, - f"{device_ids[i]} | Timestamp: {ts_values[i]} | FPS:{fps:.2f}", - (20, 40), - cv2.FONT_HERSHEY_SIMPLEX, - 0.6, - (255, 0, 50), - 2, - cv2.LINE_AA, - ) - imgs.append(frame) - - sync_status = "in sync" if abs(max(ts_values) - min(ts_values)) < 0.001 else "out of sync" - delta = max(ts_values) - min(ts_values) - color = (0, 255, 0) if sync_status == "in sync" else (0, 0, 255) - + # Build composite image side‑by‑side + imgs = [] + for i in range(len(queues)): + msg = latest_frames[i] + frame = msg.getCvFrame() + fps = fpsCounters[i].getFps() cv2.putText( - imgs[0], - f"{sync_status} | delta = {delta*1e3:.3f} ms", - (20, 80), + frame, + f"{device_ids[i]} | Timestamp: {ts_values[i]} | FPS:{fps:.2f}", + (20, 40), cv2.FONT_HERSHEY_SIMPLEX, - 0.7, - color, + 0.6, + (255, 0, 50), 2, cv2.LINE_AA, ) - - cv2.imshow("synced_view", cv2.hconcat(imgs)) - latest_frames.clear() # Wait for next batch + imgs.append(frame) + + sync_status = "in sync" if abs(max(ts_values) - min(ts_values)) < 0.001 else "out of sync" + delta = max(ts_values) - min(ts_values) + color = (0, 255, 0) if sync_status == "in sync" else (0, 0, 255) + + cv2.putText( + imgs[0], + f"{sync_status} | delta = {delta*1e3:.3f} ms", + (20, 80), + cv2.FONT_HERSHEY_SIMPLEX, + 0.7, + color, + 2, + cv2.LINE_AA, + ) + + cv2.imshow("synced_view", cv2.hconcat(imgs)) + latest_frames.clear() # Wait for next batch if cv2.waitKey(1) & 0xFF == ord("q"): break From 5dafd4c997b5ef4719e4503193bb490a991b660f Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Tue, 7 Oct 2025 16:10:56 +0200 Subject: [PATCH 05/11] Rename examples Signed-off-by: stas.bucik --- examples/cpp/Misc/MultiDevice/CMakeLists.txt | 2 +- .../MultiDevice/{multi_device.cpp => multi_device_m8_fsync.cpp} | 0 .../MultiDevice/{multi_device.py => multi_device_m8_fsync.py} | 0 3 files changed, 1 insertion(+), 1 deletion(-) rename examples/cpp/Misc/MultiDevice/{multi_device.cpp => multi_device_m8_fsync.cpp} (100%) rename examples/python/Misc/MultiDevice/{multi_device.py => multi_device_m8_fsync.py} (100%) diff --git a/examples/cpp/Misc/MultiDevice/CMakeLists.txt b/examples/cpp/Misc/MultiDevice/CMakeLists.txt index 2ce91b78f..cb7996d27 100644 --- a/examples/cpp/Misc/MultiDevice/CMakeLists.txt +++ b/examples/cpp/Misc/MultiDevice/CMakeLists.txt @@ -4,4 +4,4 @@ cmake_minimum_required(VERSION 3.10) ## function: dai_add_example(example_name example_src enable_test use_pcl) ## function: dai_set_example_test_labels(example_name ...) -dai_add_example(multi_device multi_device.cpp OFF OFF) \ No newline at end of file +dai_add_example(multi_device_m8_fsync multi_device_m8_fsync.cpp OFF OFF) \ No newline at end of file diff --git a/examples/cpp/Misc/MultiDevice/multi_device.cpp b/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp similarity index 100% rename from examples/cpp/Misc/MultiDevice/multi_device.cpp rename to examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp diff --git a/examples/python/Misc/MultiDevice/multi_device.py b/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py similarity index 100% rename from examples/python/Misc/MultiDevice/multi_device.py rename to examples/python/Misc/MultiDevice/multi_device_m8_fsync.py From 5ca9ef4371a62a67c15e913ce8e82dd311966b0d Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Wed, 8 Oct 2025 08:26:51 +0200 Subject: [PATCH 06/11] Documentation Signed-off-by: stas.bucik --- bindings/python/src/pipeline/CommonBindings.cpp | 2 +- include/depthai/common/M8FsyncRoles.hpp | 17 ++++++++++++++--- src/device/DeviceBase.cpp | 1 + 3 files changed, 16 insertions(+), 4 deletions(-) diff --git a/bindings/python/src/pipeline/CommonBindings.cpp b/bindings/python/src/pipeline/CommonBindings.cpp index 16bda83b2..ba11ff425 100644 --- a/bindings/python/src/pipeline/CommonBindings.cpp +++ b/bindings/python/src/pipeline/CommonBindings.cpp @@ -225,7 +225,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack) { // M8FsyncRole enum bindings m8FsyncRole.value("AUTO_DETECT", M8FsyncRole::AUTO_DETECT) - .value("MASTER_WITHOUT_OUTPUT", M8FsyncRole::MASTER_WITHOUT_OUTPUT) + .value("STANDALONE_NO_M8_FUNCTION", M8FsyncRole::STANDALONE_NO_M8_FUNCTION) .value("MASTER_WITH_OUTPUT", M8FsyncRole::MASTER_WITH_OUTPUT) .value("SLAVE", M8FsyncRole::SLAVE); diff --git a/include/depthai/common/M8FsyncRoles.hpp b/include/depthai/common/M8FsyncRoles.hpp index 601e7929d..767baafea 100644 --- a/include/depthai/common/M8FsyncRoles.hpp +++ b/include/depthai/common/M8FsyncRoles.hpp @@ -11,9 +11,20 @@ namespace dai { * It will choose between MASTER_WITH_OUTPUT and SLAVE. */ enum class M8FsyncRole : int32_t { + // This role is only used in setM8FsyncRole() function. + // It signals to the device to automatically detect M8 Fsync configuration. AUTO_DETECT = -1, - MASTER_WITHOUT_OUTPUT, + + // Standalone mode. + // STM generates Fsync signal, doesn't output it through M8 connector. + STANDALONE_NO_M8_FUNCTION, + + // Fsync master. + // STM generates Fsync signal and outputs it through M8 connector. MASTER_WITH_OUTPUT, + + // Fsync slave. + // Device must lock onto an external Fsync signal on the M8 connector. SLAVE, }; @@ -21,8 +32,8 @@ inline std::string toString(M8FsyncRole role) { switch(role) { case M8FsyncRole::AUTO_DETECT: return "AUTO DETECT"; - case M8FsyncRole::MASTER_WITHOUT_OUTPUT: - return "MASTER, NO OUTPUT"; + case M8FsyncRole::STANDALONE_NO_M8_FUNCTION: + return "STANDALONE, NO M8 FUNCTION"; case M8FsyncRole::MASTER_WITH_OUTPUT: return "MASTER, WITH OUTPUT"; case M8FsyncRole::SLAVE: diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 5e9d054ac..becaabed5 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1708,6 +1708,7 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { bool success = false; std::string errorMsg; + // Initialize the device (M8 Fsync slaves need to lock onto the signal first) std::tie(success, errorMsg) = pimpl->rpcCall(std::chrono::seconds(60), "waitForDeviceReady").as>(); if (!success) { From 6b695d90ed5e815b7edc238b5f57fb9011aa31c4 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Mon, 13 Oct 2025 09:27:10 +0200 Subject: [PATCH 07/11] Remove MASTER_WITHOUT_OUTPUT Signed-off-by: stas.bucik --- bindings/python/src/pipeline/CommonBindings.cpp | 3 +-- .../cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp | 2 +- .../Misc/MultiDevice/multi_device_m8_fsync.py | 2 +- include/depthai/common/M8FsyncRoles.hpp | 14 ++++---------- 4 files changed, 7 insertions(+), 14 deletions(-) diff --git a/bindings/python/src/pipeline/CommonBindings.cpp b/bindings/python/src/pipeline/CommonBindings.cpp index ba11ff425..b6578e4c9 100644 --- a/bindings/python/src/pipeline/CommonBindings.cpp +++ b/bindings/python/src/pipeline/CommonBindings.cpp @@ -225,8 +225,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack) { // M8FsyncRole enum bindings m8FsyncRole.value("AUTO_DETECT", M8FsyncRole::AUTO_DETECT) - .value("STANDALONE_NO_M8_FUNCTION", M8FsyncRole::STANDALONE_NO_M8_FUNCTION) - .value("MASTER_WITH_OUTPUT", M8FsyncRole::MASTER_WITH_OUTPUT) + .value("MASTER", M8FsyncRole::MASTER) .value("SLAVE", M8FsyncRole::SLAVE); // CameraSensorType enum bindings diff --git a/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp b/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp index cce9540b1..09dff7255 100644 --- a/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp +++ b/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp @@ -81,7 +81,7 @@ int main(int argc, char** argv) { auto role = device->getM8FsyncRole(); - if (role == dai::M8FsyncRole::MASTER_WITH_OUTPUT) { + if (role == dai::M8FsyncRole::MASTER) { master_pipelines.push_back(pipeline); } else if (role == dai::M8FsyncRole::SLAVE) { slave_pipelines.push_back(pipeline); diff --git a/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py b/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py index a0fdaaac4..f01d01781 100644 --- a/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py +++ b/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py @@ -99,7 +99,7 @@ def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.C socket = device.getConnectedCameras()[1] pipeline, out_q = createPipeline(pipeline, socket) role = device.getM8FsyncRole() - if (role == dai.M8FsyncRole.MASTER_WITH_OUTPUT): + if (role == dai.M8FsyncRole.MASTER): master_pipelines.append(pipeline) elif (role == dai.M8FsyncRole.SLAVE): slave_pipelines.append(pipeline) diff --git a/include/depthai/common/M8FsyncRoles.hpp b/include/depthai/common/M8FsyncRoles.hpp index 767baafea..e6ea8ee19 100644 --- a/include/depthai/common/M8FsyncRoles.hpp +++ b/include/depthai/common/M8FsyncRoles.hpp @@ -8,20 +8,16 @@ namespace dai { * Which Fsymc role the device will have. * * AUTO_DETECT denotes that the decision will be made by device. - * It will choose between MASTER_WITH_OUTPUT and SLAVE. + * It will choose between MASTER and SLAVE. */ enum class M8FsyncRole : int32_t { // This role is only used in setM8FsyncRole() function. // It signals to the device to automatically detect M8 Fsync configuration. AUTO_DETECT = -1, - // Standalone mode. - // STM generates Fsync signal, doesn't output it through M8 connector. - STANDALONE_NO_M8_FUNCTION, - // Fsync master. // STM generates Fsync signal and outputs it through M8 connector. - MASTER_WITH_OUTPUT, + MASTER, // Fsync slave. // Device must lock onto an external Fsync signal on the M8 connector. @@ -32,10 +28,8 @@ inline std::string toString(M8FsyncRole role) { switch(role) { case M8FsyncRole::AUTO_DETECT: return "AUTO DETECT"; - case M8FsyncRole::STANDALONE_NO_M8_FUNCTION: - return "STANDALONE, NO M8 FUNCTION"; - case M8FsyncRole::MASTER_WITH_OUTPUT: - return "MASTER, WITH OUTPUT"; + case M8FsyncRole::MASTER: + return "MASTER"; case M8FsyncRole::SLAVE: return "SLAVE"; default: From 6cf7c0680633f74867e6ca9aaf001d490ec44f66 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Mon, 13 Oct 2025 09:29:24 +0200 Subject: [PATCH 08/11] Improve error message Signed-off-by: stas.bucik --- src/device/DeviceBase.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index becaabed5..cb94a6ce8 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1712,7 +1712,7 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { std::tie(success, errorMsg) = pimpl->rpcCall(std::chrono::seconds(60), "waitForDeviceReady").as>(); if (!success) { - throw std::runtime_error("Device not ready: " + errorMsg); + throw std::runtime_error("Device " + getDeviceId() + " not ready: " + errorMsg); } // Build and start the pipeline @@ -1720,7 +1720,7 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { if(success) { pimpl->rpcCall("startPipeline"); } else { - throw std::runtime_error(errorMsg); + throw std::runtime_error("Device " + getDeviceId() + " error: " + errorMsg); return false; } From 455cabee845a569c61f103e980781fab383eae46 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Wed, 12 Nov 2025 09:30:41 +0100 Subject: [PATCH 09/11] Add M8 strobe configuration Signed-off-by: stas.bucik --- bindings/python/src/DeviceBindings.cpp | 19 +++++++++++++++++++ .../MultiDevice/multi_device_m8_fsync.cpp | 2 ++ .../Misc/MultiDevice/multi_device_m8_fsync.py | 2 ++ include/depthai/device/DeviceBase.hpp | 14 ++++++++++++++ src/device/DeviceBase.cpp | 8 ++++++++ 5 files changed, 45 insertions(+) diff --git a/bindings/python/src/DeviceBindings.cpp b/bindings/python/src/DeviceBindings.cpp index b168038c5..d269bd180 100644 --- a/bindings/python/src/DeviceBindings.cpp +++ b/bindings/python/src/DeviceBindings.cpp @@ -854,6 +854,25 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack) { }, DOC(dai, DeviceBase, getM8FsyncRole) ) + .def( + "setM8StrobeLimits", + [](DeviceBase& d, float min, float max) { + py::gil_scoped_release release; + return d.setM8StrobeLimits(min, max); + }, + py::arg("min"), + py::arg("max"), + DOC(dai, DeviceBase, setM8StrobeLimits) + ) + .def( + "setM8StrobeEnable", + [](DeviceBase& d, bool enable) { + py::gil_scoped_release release; + d.setM8StrobeEnable(enable); + }, + py::arg("enable"), + DOC(dai, DeviceBase, setM8StrobeEnable) + ) .def( "getDeviceName", [](DeviceBase& d) { diff --git a/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp b/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp index 09dff7255..4a98d25c6 100644 --- a/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp +++ b/examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp @@ -82,6 +82,8 @@ int main(int argc, char** argv) { auto role = device->getM8FsyncRole(); if (role == dai::M8FsyncRole::MASTER) { + device->setM8StrobeEnable(true); + device->setM8StrobeLimits(0.05f, 0.95f); master_pipelines.push_back(pipeline); } else if (role == dai::M8FsyncRole::SLAVE) { slave_pipelines.push_back(pipeline); diff --git a/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py b/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py index f01d01781..8fe7e0dfe 100644 --- a/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py +++ b/examples/python/Misc/MultiDevice/multi_device_m8_fsync.py @@ -100,6 +100,8 @@ def createPipeline(pipeline: dai.Pipeline, socket: dai.CameraBoardSocket = dai.C pipeline, out_q = createPipeline(pipeline, socket) role = device.getM8FsyncRole() if (role == dai.M8FsyncRole.MASTER): + device.setM8StrobeEnable(True) + device.setM8StrobeLimits(0.05, 0.95) master_pipelines.append(pipeline) elif (role == dai.M8FsyncRole.SLAVE): slave_pipelines.append(pipeline) diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 80efb2f1d..1d6a1ef6b 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -811,6 +811,20 @@ class DeviceBase { */ M8FsyncRole getM8FsyncRole(); + /** + * Sets the M8 Fsync strobe limits + * @param min Minimum strobe value in percent + * @param max Maximum strobe value in percent + * @returns Tuple of bool and string. Bool specifies if role was set without failures. String is the error message describing the failure reason. + */ + std::tuple setM8StrobeLimits(float min, float max); + + /** + * Set whether the M8 Fsync strobe should be enabled + * @param enable Enables or disables strobe + */ + void setM8StrobeEnable(bool enable); + protected: std::shared_ptr connection; diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index cb94a6ce8..474212073 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1236,6 +1236,14 @@ M8FsyncRole DeviceBase::getM8FsyncRole() { return pimpl->rpcClient->call("getM8FsyncRole"); } +std::tuple DeviceBase::setM8StrobeLimits(float min, float max) { + return pimpl->rpcClient->call("setM8StrobeLimits", min, max); +} + +void DeviceBase::setM8StrobeEnable(bool enable) { + pimpl->rpcCall("setM8StrobeEnable", enable); +} + dai::Version DeviceBase::getIMUFirmwareVersion() { isClosed(); std::string versionStr = pimpl->rpcCall("getIMUFirmwareVersion").as(); From c4a88f1af47d640f1df8357f23c66044268dab16 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Sat, 18 Oct 2025 20:57:04 +0200 Subject: [PATCH 10/11] Bump depthai-device Signed-off-by: stas.bucik --- cmake/Depthai/DepthaiDeviceRVC4Config.cmake | 2 +- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceRVC4Config.cmake b/cmake/Depthai/DepthaiDeviceRVC4Config.cmake index bd74294cd..90a1b3523 100644 --- a/cmake/Depthai/DepthaiDeviceRVC4Config.cmake +++ b/cmake/Depthai/DepthaiDeviceRVC4Config.cmake @@ -3,4 +3,4 @@ set(DEPTHAI_DEVICE_RVC4_MATURITY "snapshot") # "version if applicable" -set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+ae328e69accbf27ad21bafff806a7a549ae2f22d") +set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+2501dd359bffa6369e8f060e5723304da92927c2") diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index b2347aff8..db3a70214 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "7a638aee617e9932652076ba4a7a1862ed63f186") +set(DEPTHAI_DEVICE_SIDE_COMMIT "4235dc03b0140ffb1414c6ce0a3431ed3bc083c2") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From da661136468c18634bed0abdd4dfcd148dfdf158 Mon Sep 17 00:00:00 2001 From: "stas.bucik" Date: Mon, 20 Oct 2025 10:29:53 +0200 Subject: [PATCH 11/11] Bump workflow os version Signed-off-by: stas.bucik --- .github/workflows/test.workflow.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/test.workflow.yml b/.github/workflows/test.workflow.yml index cf15433b3..69de7c8af 100644 --- a/.github/workflows/test.workflow.yml +++ b/.github/workflows/test.workflow.yml @@ -54,7 +54,7 @@ jobs: uses: ./.github/workflows/test_child.yml with: flavor: "vanilla" - luxonis_os_versions_to_test: "['1.14.1', '1.18.3', '1.20.5']" + luxonis_os_versions_to_test: "['1.14.1', '1.18.3', 'dai-fsync-testing_11+143249837bb054e85fdace6ab00952db1cc84720']" luxonis_os_versions_to_test_rgb: "['1.20.5']" secrets: CONTAINER_REGISTRY: ${{ secrets.CONTAINER_REGISTRY }} @@ -66,7 +66,7 @@ jobs: uses: ./.github/workflows/test_child.yml with: flavor: "tsan" - luxonis_os_versions_to_test: "['1.20.5']" + luxonis_os_versions_to_test: "['dai-fsync-testing_11+143249837bb054e85fdace6ab00952db1cc84720']" secrets: CONTAINER_REGISTRY: ${{ secrets.CONTAINER_REGISTRY }} HIL_PAT_TOKEN: ${{ secrets.HIL_PAT_TOKEN }} @@ -77,7 +77,7 @@ jobs: uses: ./.github/workflows/test_child.yml with: flavor: "asan-ubsan" - luxonis_os_versions_to_test: "['1.20.5']" + luxonis_os_versions_to_test: "['dai-fsync-testing_11+143249837bb054e85fdace6ab00952db1cc84720']" secrets: CONTAINER_REGISTRY: ${{ secrets.CONTAINER_REGISTRY }} HIL_PAT_TOKEN: ${{ secrets.HIL_PAT_TOKEN }} @@ -87,7 +87,7 @@ jobs: if: needs.precheck.outputs.should_run == 'true' uses: ./.github/workflows/test_child_windows.yml with: - luxonis_os_versions_to_test: "['1.20.5']" + luxonis_os_versions_to_test: "['dai-fsync-testing_11+143249837bb054e85fdace6ab00952db1cc84720]" secrets: CONTAINER_REGISTRY: ${{ secrets.CONTAINER_REGISTRY }} HIL_PAT_TOKEN: ${{ secrets.HIL_PAT_TOKEN }}