diff --git a/depthai_examples/launch/multi_stereo_inertial_node.launch b/depthai_examples/launch/multi_stereo_inertial_node.launch
new file mode 100644
index 00000000..4e4ce1c3
--- /dev/null
+++ b/depthai_examples/launch/multi_stereo_inertial_node.launch
@@ -0,0 +1,37 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/depthai_examples/launch/stereo_inertial_node.launch b/depthai_examples/launch/stereo_inertial_node.launch
index f2515cc0..44931d95 100644
--- a/depthai_examples/launch/stereo_inertial_node.launch
+++ b/depthai_examples/launch/stereo_inertial_node.launch
@@ -1,6 +1,7 @@
+
@@ -55,7 +56,7 @@
-
+
@@ -73,6 +74,7 @@
+
diff --git a/depthai_examples/launch/stereo_inertial_node.launch.py b/depthai_examples/launch/stereo_inertial_node.launch.py
index 3ddfc2ad..a8162475 100644
--- a/depthai_examples/launch/stereo_inertial_node.launch.py
+++ b/depthai_examples/launch/stereo_inertial_node.launch.py
@@ -21,8 +21,8 @@ def generate_launch_description():
'rviz', 'stereoInertial.rviz')
default_resources_path = os.path.join(depthai_examples_path,
'resources')
-
- mxId = LaunchConfiguration('mxId', default = 'x')
+ ipAddress = LaunchConfiguration('ipAddress', default = '')
+ mxId = LaunchConfiguration('mxId', default = '')
usb2Mode = LaunchConfiguration('usb2Mode', default = False)
poeMode = LaunchConfiguration('poeMode', default = False)
@@ -78,10 +78,15 @@ def generate_launch_description():
enableRviz = LaunchConfiguration('enableRviz', default = True)
+ declare_ipAddress_cmd = DeclareLaunchArgument(
+ 'ipAddress',
+ default_value=ipAddress,
+ description='select the device by passing the IP address of the device.')
+
declare_mxId_cmd = DeclareLaunchArgument(
'mxId',
default_value=mxId,
- description='select the device by passing the MxID of the device. It will connect to first available device if left empty.')
+ description='select the device by passing the MxID of the device.')
declare_usb2Mode_cmd = DeclareLaunchArgument(
'usb2Mode',
@@ -318,7 +323,8 @@ def generate_launch_description():
stereo_node = launch_ros.actions.Node(
package='depthai_examples', executable='stereo_inertial_node',
output='screen',
- parameters=[{'mxId': mxId},
+ parameters=[{'ipAddress': ipAddress},
+ {'mxId': mxId},
{'usb2Mode': usb2Mode},
{'poeMode': poeMode},
{'resourceBaseFolder': resourceBaseFolder},
@@ -422,6 +428,7 @@ def generate_launch_description():
ld = LaunchDescription()
+ ld.add_action(declare_ipAddress_cmd)
ld.add_action(declare_mxId_cmd)
ld.add_action(declare_usb2Mode_cmd)
ld.add_action(declare_poeMode_cmd)
@@ -485,5 +492,4 @@ def generate_launch_description():
# ld.add_action(point_cloud_node)
if LaunchConfigurationEquals('enableRviz', 'True') and rviz_node is not None:
ld.add_action(rviz_node)
- return ld
-
+ return ld
\ No newline at end of file
diff --git a/depthai_examples/ros1_src/stereo_inertial_publisher.cpp b/depthai_examples/ros1_src/stereo_inertial_publisher.cpp
index 730916d9..0013c14b 100644
--- a/depthai_examples/ros1_src/stereo_inertial_publisher.cpp
+++ b/depthai_examples/ros1_src/stereo_inertial_publisher.cpp
@@ -275,7 +275,7 @@ int main(int argc, char** argv) {
ros::init(argc, argv, "stereo_inertial_node");
ros::NodeHandle pnh("~");
- std::string tfPrefix, mode, mxId, resourceBaseFolder, nnPath;
+ std::string tfPrefix, mode, mxId, resourceBaseFolder, nnPath, ipAddress;
std::string monoResolution = "720p", rgbResolution = "1080p";
int badParams = 0, stereo_fps, confidence, LRchecktresh, imuModeParam, detectionClassesCount, expTime, sensIso;
int rgbScaleNumerator, rgbScaleDinominator, previewWidth, previewHeight;
@@ -286,6 +286,7 @@ int main(int argc, char** argv) {
double dotProjectormA, floodLightmA;
std::string nnName(BLOB_NAME); // Set your blob name for the model here
+ badParams += !pnh.getParam("ipAddress", ipAddress);
badParams += !pnh.getParam("mxId", mxId);
badParams += !pnh.getParam("usb2Mode", usb2Mode);
badParams += !pnh.getParam("poeMode", poeMode);
@@ -379,7 +380,7 @@ int main(int argc, char** argv) {
std::cout << "Listing available devices..." << std::endl;
for(auto deviceInfo : availableDevices) {
std::cout << "Device Mx ID: " << deviceInfo.getMxId() << std::endl;
- if(deviceInfo.getMxId() == mxId) {
+ if(deviceInfo.getMxId() == mxId || deviceInfo.name == ipAddress) {
if(deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER) {
isDeviceFound = true;
if(poeMode) {
@@ -392,7 +393,7 @@ int main(int argc, char** argv) {
throw std::runtime_error("ros::NodeHandle() from Node \"" + pnh.getNamespace() + "\" DepthAI Device with MxId \"" + mxId
+ "\" is already booted on different process. \"");
}
- } else if(mxId.empty()) {
+ } else if(mxId.empty() && ipAddress.empty()) {
isDeviceFound = true;
device = std::make_shared(pipeline);
}
diff --git a/depthai_examples/ros2_src/stereo_inertial_publisher.cpp b/depthai_examples/ros2_src/stereo_inertial_publisher.cpp
index 26d85f4a..35d51d48 100644
--- a/depthai_examples/ros2_src/stereo_inertial_publisher.cpp
+++ b/depthai_examples/ros2_src/stereo_inertial_publisher.cpp
@@ -274,7 +274,7 @@ int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("stereo_inertial_node");
- std::string tfPrefix, mode, mxId, resourceBaseFolder, nnPath;
+ std::string tfPrefix, mode, mxId, resourceBaseFolder, nnPath, ipAddress;
std::string monoResolution = "720p", rgbResolution = "1080p";
int badParams = 0, stereo_fps, confidence, LRchecktresh, imuModeParam, detectionClassesCount, expTime, sensIso;
int rgbScaleNumerator, rgbScaleDinominator, previewWidth, previewHeight;
@@ -285,6 +285,7 @@ int main(int argc, char** argv) {
double dotProjectormA, floodLightmA;
std::string nnName(BLOB_NAME); // Set your blob name for the model here
+ node->declare_parameter("ipAddress", "");
node->declare_parameter("mxId", "");
node->declare_parameter("usb2Mode", false);
node->declare_parameter("poeMode", false);
@@ -329,6 +330,7 @@ int main(int argc, char** argv) {
// updating parameters if defined in launch file.
+ node->get_parameter("ipAddress", ipAddress);
node->get_parameter("mxId", mxId);
node->get_parameter("usb2Mode", usb2Mode);
node->get_parameter("poeMode", poeMode);
@@ -392,7 +394,7 @@ int main(int argc, char** argv) {
dai::Pipeline pipeline;
int width, height;
bool isDeviceFound = false;
- std::tie(pipeline, width, height) = createPipeline(enableDepth,
+ std::tie(pipeline, width, height) = createPipeline(enableDepth,
enableSpatialDetection,
lrcheck,
extended,
@@ -418,7 +420,7 @@ int main(int argc, char** argv) {
std::cout << "Listing available devices..." << std::endl;
for(auto deviceInfo : availableDevices) {
std::cout << "Device Mx ID: " << deviceInfo.getMxId() << std::endl;
- if(deviceInfo.getMxId() == mxId) {
+ if(deviceInfo.getMxId() == mxId || deviceInfo.name == ipAddress) {
if(deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER) {
isDeviceFound = true;
if(poeMode) {
@@ -428,13 +430,15 @@ int main(int argc, char** argv) {
}
break;
} else if(deviceInfo.state == X_LINK_BOOTED) {
- throw std::runtime_error("\" DepthAI Device with MxId \"" + mxId + "\" is already booted on different process. \"");
+ throw std::runtime_error("\" DepthAI Device with MxId \"" + mxId
+ + "\" is already booted on different process. \"");
}
- } else if(mxId == "x") {
+ } else if(mxId.empty() && ipAddress.empty()) {
isDeviceFound = true;
device = std::make_shared(pipeline);
}
}
+
if(!isDeviceFound) {
throw std::runtime_error("\" DepthAI Device with MxId \"" + mxId + "\" not found. \"");
}
@@ -443,7 +447,6 @@ int main(int argc, char** argv) {
std::cout << "Device USB status: " << usbStrings[static_cast(device->getUsbSpeed())] << std::endl;
}
-
// Apply camera controls
auto controlQueue = device->getInputQueue("control");