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

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions bindings/python/src/DeviceBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -830,6 +830,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) {
Expand Down
7 changes: 7 additions & 0 deletions bindings/python/src/pipeline/CommonBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -50,6 +51,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack) {
py::class_<Quaterniond> quaterniond(m, "Quaterniond", DOC(dai, Quaterniond));
py::class_<Size2f> size2f(m, "Size2f", DOC(dai, Size2f));
py::enum_<CameraBoardSocket> cameraBoardSocket(m, "CameraBoardSocket", DOC(dai, CameraBoardSocket));
py::enum_<M8FsyncRole> m8FsyncRole(m, "M8FsyncRole", DOC(dai, M8FsyncRole));
py::enum_<ConnectionInterface> connectionInterface(m, "connectionInterface", DOC(dai, ConnectionInterface));
py::enum_<CameraSensorType> cameraSensorType(m, "CameraSensorType", DOC(dai, CameraSensorType));
py::enum_<CameraImageOrientation> cameraImageOrientation(m, "CameraImageOrientation", DOC(dai, CameraImageOrientation));
Expand Down Expand Up @@ -221,6 +223,11 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack) {
});
HEDLEY_DIAGNOSTIC_POP

// M8FsyncRole enum bindings
m8FsyncRole.value("AUTO_DETECT", M8FsyncRole::AUTO_DETECT)
.value("MASTER", M8FsyncRole::MASTER)
.value("SLAVE", M8FsyncRole::SLAVE);

// CameraSensorType enum bindings
cameraSensorType.value("COLOR", CameraSensorType::COLOR)
.value("MONO", CameraSensorType::MONO)
Expand Down
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceRVC4Config.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@
set(DEPTHAI_DEVICE_RVC4_MATURITY "snapshot")

# "version if applicable"
set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+cd0fc231d8c860acf11ab424109d7e42500626ae")
set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+9c855c6821899797d55e3c7f6efa30bdba0e704f")
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceSideConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot")

# "full commit hash of device side binary"
set(DEPTHAI_DEVICE_SIDE_COMMIT "0ada9b9800478cf2c7056cea5c2bab2c8f6a2cbd")
set(DEPTHAI_DEVICE_SIDE_COMMIT "46e8c42f3fa78baedd7595a290d197277b7ead5a")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
3 changes: 2 additions & 1 deletion examples/cpp/Misc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,5 @@ project(misc_examples)
cmake_minimum_required(VERSION 3.10)

add_subdirectory(AutoReconnect)
add_subdirectory(Projectors)
add_subdirectory(Projectors)
add_subdirectory(MultiDevice)
7 changes: 7 additions & 0 deletions examples/cpp/Misc/MultiDevice/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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_m8_fsync multi_device_m8_fsync.cpp OFF OFF)
192 changes: 192 additions & 0 deletions examples/cpp/Misc/MultiDevice/multi_device_m8_fsync.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,192 @@
#include <algorithm>
#include <chrono>
#include <cstdlib>
#include <iostream>
#include <memory>
#include <opencv2/core.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/opencv.hpp>
#include <stdexcept>
#include <utility>
#include <vector>
#include <string>

#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"
#include "depthai/pipeline/datatype/ImgFrame.hpp"
#include "depthai/pipeline/node/Camera.hpp"
#include "depthai/xlink/XLinkConnection.hpp"

class FPSCounter {
public:
std::vector<std::chrono::time_point<std::chrono::steady_clock>> 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<std::chrono::microseconds>(frameTimes.back() - frameTimes.front()).count();
}
};


int main(int argc, char** argv) {

if (argc < 4) {
std::cout << "Usage: " << argv[0] << " <target_fps> <device_ip_1> <device_ip_2> [device_ip_3] ..." << std::endl;
std::exit(0);
}

float TARGET_FPS = std::stof(argv[1]);

std::vector<dai::DeviceInfo> DEVICE_INFOS;
for (int i = 2; i < argc; i++) {
DEVICE_INFOS.emplace_back(std::string(argv[i]));
}

std::vector<std::shared_ptr<dai::MessageQueue>> queues;
std::vector<dai::Pipeline> master_pipelines;
std::vector<dai::Pipeline> slave_pipelines;
std::vector<std::string> device_ids;

for (auto deviceInfo : DEVICE_INFOS)
{
auto pipeline = dai::Pipeline(std::make_shared<dai::Device>(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<dai::node::Camera>()->build(socket, std::nullopt, TARGET_FPS);
auto out_q = cam->requestOutput(std::make_pair(640, 480), dai::ImgFrame::Type::NV12, dai::ImgResizeMode::STRETCH)->createOutputQueue();

auto role = device->getM8FsyncRole();

if (role == dai::M8FsyncRole::MASTER) {
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<int, std::shared_ptr<dai::ImgFrame>> latest_frames;
std::vector<bool> receivedFrames;
std::vector<FPSCounter> fpsCounters(queues.size());

for(auto q : queues) {
receivedFrames.push_back(false);
}

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<dai::ImgFrame>(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<std::chrono::time_point<std::chrono::steady_clock>> ts_values;
for (auto pair : latest_frames) {
auto f = pair.second;
ts_values.push_back(f->getTimestamp(dai::CameraExposureOffset::END));
}

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::chrono::microseconds>(
*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<std::chrono::microseconds>(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;
}
Loading