Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Connect to a Specific Device using IP address as input #153

Open
wants to merge 12 commits into
base: ros-release
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 10 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
37 changes: 37 additions & 0 deletions depthai_examples/launch/multi_stereo_inertial_node.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<?xml version="1.0"?>
<launch>
<!-- Multiple camera args -->
<arg name="enable_camera1" default="true"/>
<arg name="enable_camera2" default="false"/>
<arg name="useWithIP_camera1" default="false"/>
<arg name="useWithIP_camera2" default="false"/>
<arg name="ip_address_camera1" default=""/>
<arg name="ip_address_camera2" default=""/>
<arg name="useWithMxId_camera1" default="false"/>
<arg name="useWithMxId_camera2" default="false"/>
<arg name="mxId_camera1" default=""/>
<arg name="mxId_camera2" default=""/>
<arg name="tf_prefix_camera1" default="oak_front"/>
<arg name="tf_prefix_camera2" default="oak_back"/>

<!-- First Camera -->
<include if="$(eval arg('enable_camera1') == true)" file="$(find depthai_examples)/launch/stereo_inertial_node.launch">
<arg name="tf_prefix" value="$(arg tf_prefix_camera1)" />
<arg name="useWithIP" value="$(arg useWithIP_camera1)"/>
<arg name="ipAddress" value="$(arg ip_address_camera1)"/>
<arg name="useWithMxId" value="$(arg useWithMxId_camera1)"/>
<arg name="mxId" value="$(arg mxId_camera1)"/>
</include>

<!-- Second Camera -->
<include if="$(eval arg('enable_camera2') == true)" file="$(find depthai_examples)/launch/stereo_inertial_node.launch">
<arg name="tf_prefix" value="$(arg tf_prefix_camera2)" />
<arg name="useWithIP" value="$(arg useWithIP_camera2)"/>
<arg name="ipAddress" value="$(arg ip_address_camera2)"/>
<arg name="useWithMxId" value="$(arg useWithMxId_camera2)"/>
<arg name="mxId" value="$(arg mxId_camera2)"/>
</include>

<!-- More cameras can be added in the same fashion -->

</launch>
4 changes: 3 additions & 1 deletion depthai_examples/launch/stereo_inertial_node.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<?xml version="1.0"?>
<launch>
<!-- <args for urdf/> -->
<arg name="ipAddress" default=""/>
<arg name="mxId" default=""/>
<arg name="usb2Mode" default="false"/>
<arg name="poeMode" default="false"/>
Expand Down Expand Up @@ -55,7 +56,7 @@
<arg name="enableFloodLight" default="false"/>
<arg name="dotProjectormA" default="200.0"/>
<arg name="floodLightmA" default="200.0"/>
<arg name="enableRviz" default="true"/>
<arg name="enableRviz" default="false"/>
<arg name="enableMarkerPublish" default="false" />

<include file="$(find depthai_bridge)/launch/urdf.launch">
Expand All @@ -73,6 +74,7 @@

<!-- launch-prefix="xterm -e gdb (add [- - args] without space) -->
<node name="stereo_inertial_publisher" pkg="depthai_examples" type="stereo_inertial_node" output="screen" required="true">
<param name="ipAddress" value="$(arg ipAddress)"/>
<param name="mxId" value="$(arg mxId)"/>
<param name="usb2Mode" value="$(arg usb2Mode)"/>
<param name="poeMode" value="$(arg poeMode)"/>
Expand Down
16 changes: 11 additions & 5 deletions depthai_examples/launch/stereo_inertial_node.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ def generate_launch_description():
'rviz', 'stereoInertial.rviz')
default_resources_path = os.path.join(depthai_examples_path,
'resources')

ipAddress = LaunchConfiguration('ipAddress', default = 'x')
mxId = LaunchConfiguration('mxId', default = 'x')
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it is x here. you are checking for empty in the code.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@saching13 Good catch! I fixed it with the new commit

usb2Mode = LaunchConfiguration('usb2Mode', default = False)
poeMode = LaunchConfiguration('poeMode', default = False)
Expand Down Expand Up @@ -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',
Expand Down Expand Up @@ -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},
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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
7 changes: 4 additions & 3 deletions depthai_examples/ros1_src/stereo_inertial_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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);
Expand Down Expand Up @@ -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) {
Expand All @@ -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<dai::Device>(pipeline);
}
Expand Down
19 changes: 11 additions & 8 deletions depthai_examples/ros2_src/stereo_inertial_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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,
Expand All @@ -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) {
Expand All @@ -428,22 +430,23 @@ 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("ros::NodeHandle() from Node \"" + pnh.getNamespace() + "\" 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<dai::Device>(pipeline);
}
}

if(!isDeviceFound) {
throw std::runtime_error("\" DepthAI Device with MxId \"" + mxId + "\" not found. \"");
throw std::runtime_error("ros::NodeHandle() from Node \"" + pnh.getNamespace() + "\" DepthAI Device with MxId \"" + mxId + "\" not found. \"");
}

if(!poeMode) {
std::cout << "Device USB status: " << usbStrings[static_cast<int32_t>(device->getUsbSpeed())] << std::endl;
}


// Apply camera controls
auto controlQueue = device->getInputQueue("control");

Expand Down Expand Up @@ -676,4 +679,4 @@ int main(int argc, char** argv) {
}

return 0;
}
}