Skip to content

Commit

Permalink
Final changes from mxId to deviceId
Browse files Browse the repository at this point in the history
  • Loading branch information
Matevz Morato committed Jan 8, 2025
1 parent 47b30ec commit 859d7ca
Show file tree
Hide file tree
Showing 11 changed files with 36 additions and 36 deletions.
2 changes: 1 addition & 1 deletion bindings/python/src/DeviceBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -462,7 +462,7 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){
.def_static("getAllAvailableDevices", &DeviceBase::getAllAvailableDevices, DOC(dai, DeviceBase, getAllAvailableDevices))
.def_static("getEmbeddedDeviceBinary", py::overload_cast<bool, OpenVINO::Version>(&DeviceBase::getEmbeddedDeviceBinary), py::arg("usb2Mode"), py::arg("version") = OpenVINO::VERSION_UNIVERSAL, DOC(dai, DeviceBase, getEmbeddedDeviceBinary))
.def_static("getEmbeddedDeviceBinary", py::overload_cast<DeviceBase::Config>(&DeviceBase::getEmbeddedDeviceBinary), py::arg("config"), DOC(dai, DeviceBase, getEmbeddedDeviceBinary, 2))
.def_static("getDeviceByMxId", &DeviceBase::getDeviceByMxId, py::arg("mxId"), DOC(dai, DeviceBase, getDeviceByMxId))
.def_static("getDeviceByDeviceId", &DeviceBase::getDeviceByDeviceId, py::arg("deviceId"), DOC(dai, DeviceBase, getDeviceByDeviceId))
.def_static("getAllConnectedDevices", &DeviceBase::getAllConnectedDevices, DOC(dai, DeviceBase, getAllConnectedDevices))
.def_static("getGlobalProfilingData", &DeviceBase::getGlobalProfilingData, DOC(dai, DeviceBase, getGlobalProfilingData))

Expand Down
4 changes: 2 additions & 2 deletions bindings/python/src/XLinkBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void XLinkBindings::bind(pybind11::module &m, void *pCallstack)
py::arg("platform"),
py::arg("status"),
DOC(dai, DeviceInfo, DeviceInfo, 2))
.def(py::init<std::string>(), py::arg("mxidOrName"), DOC(dai, DeviceInfo, DeviceInfo, 3))
.def(py::init<std::string>(), py::arg("deviceIdOrName"), DOC(dai, DeviceInfo, DeviceInfo, 3))
.def(py::init<const deviceDesc_t&>(), DOC(dai, DeviceInfo, DeviceInfo, 4))
.def("getMxId", [](DeviceInfo& info) { PyErr_WarnEx(PyExc_DeprecationWarning, "getMxId is deprecated, use getDeviceId instead.", 1); return info.getMxId(); }, DOC(dai, DeviceInfo, getMxId))
.def("getDeviceId", &DeviceInfo::getDeviceId, DOC(dai, DeviceInfo, getDeviceId))
Expand Down Expand Up @@ -147,7 +147,7 @@ void XLinkBindings::bind(pybind11::module &m, void *pCallstack)
.def(py::init<const DeviceInfo &>())
.def_static("getAllConnectedDevices", &XLinkConnection::getAllConnectedDevices, py::arg("state") = X_LINK_ANY_STATE, py::arg("skipInvalidDevices") = true)
.def_static("getFirstDevice", &XLinkConnection::getFirstDevice, py::arg("state") = X_LINK_ANY_STATE, py::arg("skipInvalidDevice") = true)
.def_static("getDeviceByMxId", &XLinkConnection::getDeviceByMxId, py::arg("mxId"), py::arg("state") = X_LINK_ANY_STATE, py::arg("skipInvalidDevice") = true)
.def_static("getDeviceByDeviceId", &XLinkConnection::getDeviceByDeviceId, py::arg("deviceId"), py::arg("state") = X_LINK_ANY_STATE, py::arg("skipInvalidDevice") = true)
.def_static("bootBootloader", &XLinkConnection::bootBootloader, py::arg("devInfo"))
.def_static("getGlobalProfilingData", &XLinkConnection::getGlobalProfilingData, DOC(dai, XLinkConnection, getGlobalProfilingData))
;
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/utilities/cam_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ def socket_to_socket_opt(socket: dai.CameraBoardSocket) -> str:
signal.signal(signal.SIGINT, exit_cleanly)

# Connect to device, so that we can get connected cameras in case of no args
success, device_info = dai.Device.getDeviceByMxId(args.device)
success, device_info = dai.Device.getDeviceByDeviceId(args.device)
dai_device_args = []
if success:
dai_device_args.append(device_info)
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/utilities/device_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ def __init__(self, window):
self.infos = []
layout = [
[sg.Text("Select an OAK camera you would like to connect to.", font=('Arial', 10, 'bold'))],
[sg.Table(values=[], headings=["MxId", "Name", "State"],
[sg.Table(values=[], headings=["DeviceId", "Name", "State"],
# col_widths=[25, 17, 17],
# def_col_width=25,
# max_col_width=200,
Expand Down
4 changes: 2 additions & 2 deletions bindings/python/utilities/stress_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ class PipelineContext:
q_name_yolo_passthrough: Optional[str] = None
"""The name of the queue that the YOLO spatial detection network passthrough is connected to."""

def stress_test(mxid: str = ""):
def stress_test(deviceId: str = ""):
# Parse args
import argparse
parser = argparse.ArgumentParser()
Expand All @@ -156,7 +156,7 @@ def stress_test(mxid: str = ""):
exp_time = 20000

import time
success, device_info = dai.Device.getDeviceByMxId(mxid)
success, device_info = dai.Device.getDeviceByDeviceId(deviceId)
cam_args = [] # Device info or no args at all
if success:
cam_args.append(device_info)
Expand Down
6 changes: 3 additions & 3 deletions include/depthai/device/DeviceBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,11 +119,11 @@ class DeviceBase {
static std::tuple<bool, DeviceInfo> getFirstAvailableDevice(bool skipInvalidDevice = true);

/**
* Finds a device by MX ID. Example: 14442C10D13EABCE00
* @param mxId MyraidX ID which uniquely specifies a device
* Finds a device by Device ID. Example: 14442C10D13EABCE00
* @param deviceId Device ID which uniquely specifies a device
* @returns Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device
*/
static std::tuple<bool, DeviceInfo> getDeviceByMxId(std::string mxId);
static std::tuple<bool, DeviceInfo> getDeviceByDeviceId(std::string deviceId);

/**
* Returns all available devices
Expand Down
14 changes: 7 additions & 7 deletions include/depthai/xlink/XLinkConnection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ namespace dai {
*/
struct DeviceInfo {
DeviceInfo() = default;
DeviceInfo(std::string name, std::string mxid, XLinkDeviceState_t state, XLinkProtocol_t protocol, XLinkPlatform_t platform, XLinkError_t status);
DeviceInfo(std::string name, std::string deviceId, XLinkDeviceState_t state, XLinkProtocol_t protocol, XLinkPlatform_t platform, XLinkError_t status);
/**
* Creates a DeviceInfo by checking whether supplied parameter is a MXID or IP/USB name
* @param mxidOrName Either MXID, IP Address or USB port name
* Creates a DeviceInfo by checking whether supplied parameter is a DeviceID or IP/USB name
* @param deviceIdOrName Either DeviceId, IP Address or USB port name
*/
explicit DeviceInfo(std::string mxidOrName);
explicit DeviceInfo(std::string deviceIdOrName);
explicit DeviceInfo(const deviceDesc_t& desc);
deviceDesc_t getXLinkDeviceDesc() const;
[[deprecated("Use getDeviceId() instead")]] std::string getMxId() const;
Expand Down Expand Up @@ -70,13 +70,13 @@ class XLinkConnection {
static std::tuple<bool, DeviceInfo> getFirstDevice(XLinkDeviceState_t state = X_LINK_ANY_STATE, bool skipInvalidDevices = true);

/**
* Finds a device by MX ID. Example: 14442C10D13EABCE00
* @param mxId MyraidX ID which uniquely specifies a device
* Finds a device by Device ID. Example: 14442C10D13EABCE00
* @param deviceId Device ID which uniquely specifies a device
* @param state Which state should the device be in
* @param skipInvalidDevices Whether or not to skip devices that cannot be fully detected
* @returns Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device
*/
static std::tuple<bool, DeviceInfo> getDeviceByMxId(std::string mxId, XLinkDeviceState_t state = X_LINK_ANY_STATE, bool skipInvalidDevice = true);
static std::tuple<bool, DeviceInfo> getDeviceByDeviceId(std::string deviceId, XLinkDeviceState_t state = X_LINK_ANY_STATE, bool skipInvalidDevice = true);

/**
* Tries booting the given device into bootloader state
Expand Down
8 changes: 4 additions & 4 deletions src/device/DeviceBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -246,14 +246,14 @@ std::vector<DeviceInfo> DeviceBase::getAllConnectedDevices() {
return XLinkConnection::getAllConnectedDevices();
}

// First tries to find UNBOOTED device with mxId, then BOOTLOADER device with mxId
std::tuple<bool, DeviceInfo> DeviceBase::getDeviceByMxId(std::string mxId) {
// First tries to find UNBOOTED device with deviceId, then BOOTLOADER device with deviceId
std::tuple<bool, DeviceInfo> DeviceBase::getDeviceByDeviceId(std::string deviceId) {
std::vector<DeviceInfo> availableDevices;
auto states = {X_LINK_UNBOOTED, X_LINK_BOOTLOADER, X_LINK_GATE};
bool found;
DeviceInfo dev;
for(const auto& state : states) {
std::tie(found, dev) = XLinkConnection::getDeviceByMxId(mxId, state);
std::tie(found, dev) = XLinkConnection::getDeviceByDeviceId(deviceId, state);
if(found) return {true, dev};
}
return {false, DeviceInfo()};
Expand Down Expand Up @@ -620,7 +620,7 @@ void DeviceBase::closeImpl() {
bool found = false;
do {
DeviceInfo rebootingDeviceInfo;
std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByMxId(deviceInfo.getDeviceId(), X_LINK_ANY_STATE, false);
std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByDeviceId(deviceInfo.getDeviceId(), X_LINK_ANY_STATE, false);
if(found && (rebootingDeviceInfo.state == X_LINK_UNBOOTED || rebootingDeviceInfo.state == X_LINK_BOOTLOADER)) {
pimpl->logger.trace("Found rebooting device in {}ns", duration_cast<nanoseconds>(steady_clock::now() - t1).count());
DeviceBase rebootingDevice(config, rebootingDeviceInfo, firmwarePath, true);
Expand Down
16 changes: 8 additions & 8 deletions src/opencv/HolisticRecordReplay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
namespace dai {
namespace utility {

bool setupHolisticRecord(Pipeline& pipeline, const std::string& mxId, RecordConfig& recordConfig, std::unordered_map<std::string, std::string>& outFilenames) {
bool setupHolisticRecord(Pipeline& pipeline, const std::string& deviceId, RecordConfig& recordConfig, std::unordered_map<std::string, std::string>& outFilenames) {
auto sources = pipeline.getSourceNodes();
const auto recordPath = recordConfig.outputDir;
try {
Expand All @@ -33,7 +33,7 @@ bool setupHolisticRecord(Pipeline& pipeline, const std::string& mxId, RecordConf
}
NodeRecordParams nodeParams = nodeS->getNodeRecordParams();
std::string nodeName = (nodeParams.video ? "v_" : "b_") + nodeParams.name;
std::string filePath = platform::joinPaths(recordPath, (mxId + "_").append(nodeName));
std::string filePath = platform::joinPaths(recordPath, (deviceId + "_").append(nodeName));
outFilenames[nodeName] = filePath;
if(std::dynamic_pointer_cast<node::Camera>(node) != nullptr || std::dynamic_pointer_cast<node::ColorCamera>(node) != nullptr
|| std::dynamic_pointer_cast<node::MonoCamera>(node) != nullptr) {
Expand Down Expand Up @@ -77,15 +77,15 @@ bool setupHolisticRecord(Pipeline& pipeline, const std::string& mxId, RecordConf
nodeS->getRecordOutput().link(recordNode->input);
}
}
outFilenames["record_config"] = platform::joinPaths(recordPath, mxId + "_record_config.json");
outFilenames["record_config"] = platform::joinPaths(recordPath, deviceId + "_record_config.json");
} catch(const std::runtime_error& e) {
recordConfig.state = RecordConfig::RecordReplayState::NONE;
spdlog::warn("Record disabled: {}", e.what());
return false;
}
// Write recordConfig to output dir
try {
std::ofstream file(Path(platform::joinPaths(recordPath, mxId + "_record_config.json")));
std::ofstream file(Path(platform::joinPaths(recordPath, deviceId + "_record_config.json")));
json j = recordConfig;
file << j.dump(4);
} catch(const std::exception& e) {
Expand All @@ -97,10 +97,10 @@ bool setupHolisticRecord(Pipeline& pipeline, const std::string& mxId, RecordConf

bool setupHolisticReplay(Pipeline& pipeline,
std::string replayPath,
const std::string& mxId,
const std::string& deviceId,
RecordConfig& recordConfig,
std::unordered_map<std::string, std::string>& outFilenames) {
UNUSED(mxId);
UNUSED(deviceId);
const std::string rootPath = platform::getDirFromPath(replayPath);
auto sources = pipeline.getSourceNodes();
try {
Expand Down Expand Up @@ -139,7 +139,7 @@ bool setupHolisticReplay(Pipeline& pipeline,
}
NodeRecordParams nodeParams = nodeS->getNodeRecordParams();
// Needed for muti-device recordings, not yet supported
// std::string nodeName = (mxId + "_").append(nodeParams.name);
// std::string nodeName = (deviceId + "_").append(nodeParams.name);
std::string nodeName = nodeParams.name;
pipelineFilenames.push_back(nodeName);
nodeNames.push_back(nodeParams.name);
Expand All @@ -151,7 +151,7 @@ bool setupHolisticReplay(Pipeline& pipeline,
outFiles.reserve(sources.size() + 1);
if(!useTar || allMatch(tarNodenames, pipelineFilenames)) {
for(auto& nodeName : nodeNames) {
// auto filename = (mxId + "_").append(nodeName);
// auto filename = (deviceId + "_").append(nodeName);
auto filename = nodeName;
if(useTar) {
inFiles.push_back(tarRoot + filename + ".mp4");
Expand Down
4 changes: 2 additions & 2 deletions src/utility/HolisticRecordReplay.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@ namespace dai {
namespace utility {

#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT
bool setupHolisticRecord(Pipeline& pipeline, const std::string& mxId, RecordConfig& recordConfig, std::unordered_map<std::string, std::string>& outFilenames);
bool setupHolisticRecord(Pipeline& pipeline, const std::string& deviceId, RecordConfig& recordConfig, std::unordered_map<std::string, std::string>& outFilenames);
bool setupHolisticReplay(Pipeline& pipeline,
std::string replayPath,
const std::string& mxId,
const std::string& deviceId,
RecordConfig& recordConfig,
std::unordered_map<std::string, std::string>& outFilenames);
#endif
Expand Down
10 changes: 5 additions & 5 deletions src/xlink/XLinkConnection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,13 @@ DeviceInfo::DeviceInfo(std::string name, std::string deviceId, XLinkDeviceState_

DeviceInfo::DeviceInfo(std::string deviceIdOrName) {
// Parse parameter and set to ip if any dots found
// mxid doesn't have a dot in the name
// deviceId doesn't have a dot in the name
if(deviceIdOrName.find(".") != std::string::npos) {
// This is reasoned as an IP address or USB path (name). Set rest of info accordingly
name = std::move(deviceIdOrName);
deviceId = "";
} else {
// This is reasoned as mxid
// This is reasoned as deviceId
name = "";
deviceId = std::move(deviceIdOrName);
}
Expand Down Expand Up @@ -273,11 +273,11 @@ std::tuple<bool, DeviceInfo> XLinkConnection::getFirstDevice(XLinkDeviceState_t
return {false, {}};
}

std::tuple<bool, DeviceInfo> XLinkConnection::getDeviceByMxId(std::string mxId, XLinkDeviceState_t state, bool skipInvalidDevices) {
std::tuple<bool, DeviceInfo> XLinkConnection::getDeviceByDeviceId(std::string deviceId, XLinkDeviceState_t state, bool skipInvalidDevices) {
initialize();

DeviceInfo dev;
dev.deviceId = mxId;
dev.deviceId = deviceId;
dev.state = state;

deviceDesc_t desc = {};
Expand Down Expand Up @@ -422,7 +422,7 @@ void XLinkConnection::close() {
bool found = false;
do {
DeviceInfo rebootingDeviceInfo;
std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByMxId(deviceInfo.getDeviceId(), X_LINK_ANY_STATE, false);
std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByDeviceId(deviceInfo.getDeviceId(), X_LINK_ANY_STATE, false);
if(found) {
if(rebootingDeviceInfo.state == X_LINK_UNBOOTED || rebootingDeviceInfo.state == X_LINK_BOOTLOADER) {
break;
Expand Down

0 comments on commit 859d7ca

Please sign in to comment.