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

Conversation

samialperen
Copy link

…idual cameras with IP. In this way, we can connect to multiple cameras easier by specifying their IP adress. Device manager under depthai-python was used to assign static IP addresses to each camera

…idual cameras with IP. In this way, we can connect to multiple cameras easier by specifying their IP adress. Device manager under depthai-python was used to assign static IP addresses to each camera
Copy link
Contributor

@saching13 saching13 left a comment

Choose a reason for hiding this comment

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

Thanks for the PR.

As of the IP address based access I can accept that. But can you also modify to include MxID based device selection for PoE too ?

And also would need the same changes for stereo_inertial_publisher.cpp in ros2.

As of the launch file. I would pass on that for now. It still limits to 3 devices. If you use the single device launch file and call it multiple times in an another launch file it should still do the same job. So the users can call it the number of devices they have. be it 3 or 10.

depthai_examples/launch/multi_stereo_inertial_node.launch Outdated Show resolved Hide resolved
depthai_examples/ros1_src/stereo_inertial_publisher.cpp Outdated Show resolved Hide resolved
…nnect one randomly. Also checked different possibilities to cover all conditional branches and added necessary error prints
@samialperen
Copy link
Author

@saching13 how about the new commit? Now we have three way of connecting
1-) useWithIp
2-) useWithMxID
3-) useWithIP = false, useWithMxId = false --> current method in the file listing all available devices and connecting one randomly

If it looks good, I will bring changes to ROS2 code too.

@zflat
Copy link

zflat commented Nov 7, 2022

@samialperen I'm interested in using this with ROS2. If you push an update to this branch I can test it out because I want to launch multiple OAK-D cameras and specify the IP address for each camera to launch. In my use-case I will associate specific IP addresses with specific top prefixes for further processing in a ROS node.

@samialperen
Copy link
Author

@zflat heyo! I will try to bring the changes to ROS2 either tonight or tomorrow night. Stay tuned and thanks for offering testing it out.

@samialperen
Copy link
Author

@zflat @saching13 ROS2 changes were added with the last commit and tested in ROS2 Foxy.

@saching13
Copy link
Contributor

@samialperen All looks good.
Can you also update the original stereo_inertial_node.launch file too and use it in the multiple ? feel free to add argument to disable the urdf if not needed.

…s and tested in noetic. Multi node now is calling stereo inertial node multiple times to give an idea to users how they can use multiple cameras
@samialperen
Copy link
Author

@saching13 Done! Tested with a single USB in ROS noetic, and it is working fine. I did not have a chance to test multi-launch with multiple cameras since I no longer have the same setup.

@zflat
Copy link

zflat commented Nov 10, 2022

@samialperen I did some initial testing and have some feedback

Need to check DeviceInfo after connecting to the camera

I found that if you check deviceInfo.status right after it is created with auto deviceInfo = dai::DeviceInfo(ipAddress); then the status has a value of 0. However, if you create the Device connection with device = std::make_shared<dai::Device>(pipeline, deviceInfo); and then check the associated device info the value I got was 1 using device.getDeviceInfo().state. Is this specific to the POE camera and different than the USB camera?

Need a try/catch and retry logic

I know this is just an example, but it would help if the application could gracefully handle re-trying if a connection can not be made or re-connecting if the connection is broken.

Please follow consistent capitalization for ros params

The new ros params like useWithIp should be use_with_ip to match the style of existing params like cam_pos_x.

@samialperen
Copy link
Author

@zflat heyo! Thanks for the feedback.

  • I am not sure about deviceInfo.status. That is why I decided to go with deviceInfo.state which helps with better control.
  • I agree, but to keep this PR simple, I will suggest to open a feature request. We can add that as a new feature to fix connection failures to the camera.
  • They are already consistent. Check enableDotProjector and other ros params.

@zflat
Copy link

zflat commented Nov 10, 2022

@samialperen Oops, I meant to write state and not status.

This is what I am logging out after I connect:

RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "deviceInfo.state: %d", device.getDeviceInfo().state)

That logs "deviceInfo.state: 1" after dai::Device device(pipeline, deviceInfo) returns.

if(useWithIP) // Connecting to a camera with specific IP, requires static IP config beforehand
{
auto deviceInfo = dai::DeviceInfo(ipAddress);
if(deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
Copy link

Choose a reason for hiding this comment

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

The value of deviceInfo.state is always 0 here so the exception "Could NOT connect to device with IP Address" is always thrown. If we want to check if another process already has a connection, maybe we should do something like this:

    if(useWithIP) {
        auto connectionInfo = dai::Device::getAllConnectedDevices();
        for (auto const& info : connectionInfo)
        {
            if (info.name == ipAddress && info.state == X_LINK_BOOTED) {
                // Throw exception here....
            }
        }
        auto deviceInfo = dai::DeviceInfo(ipAddress);
        if(poeMode) {
            device = std::make_shared<dai::Device>(pipeline, deviceInfo);
        } else {
            device = std::make_shared<dai::Device>(pipeline, deviceInfo, usb2Mode);
        }
        if(device.getDeviceInfo().state == X_LINK_BOOTED) {
            std::cout << "Device found with IP Address: " << ipAddress <<  std::endl;
        }
    else if(useWithMxId) {
        // ...
    }

Copy link
Author

Choose a reason for hiding this comment

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

@zflat Did you assign a static ip to your camera using depthai device manager? I tested it with my camera and it seems to be working. deviceInfo.state is actually an enum, so if it returns 1, it can take the following values
image
so 1 probably corresponds to X_LINK_BOOTED, which kinda tells me that you have not used device manager, because once you use device manager to assign static IP, deviceInfo.state becomes X_LINK_FLASH_BOOTED.

Copy link

Choose a reason for hiding this comment

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

Yes, I did assign a static IP.
I tested this code on an OAK-1 (actually copy and pasted the logic to rgb_publisher.cpp because it can't use a pipeline that is set up for steroe) and also an OAK-D.

OAK-1
Screenshot from 2022-11-09 16-29-06

OAK-D
Screenshot from 2022-11-11 12-08-53

Copy link
Author

Choose a reason for hiding this comment

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

@zflat Could you try to flash the newest bootloader? I remember I had a problem connecting to my device with IP address before updating the bootloader. If it doesn't solve the issue, I should have OAK (Series 1) POE lying somewhere. I will test it with that guy.

Copy link

Choose a reason for hiding this comment

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

I have tried flashing a new bootloader and I just get an error popup and then a message to the terminal that it was cancelled. Sorry I can't be of more help.

Copy link
Author

Choose a reason for hiding this comment

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

@zflat No problem! Lemme give it a try.

Copy link
Author

Choose a reason for hiding this comment

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

@zflat You are right. Somehow, deviceInfo.state returns 0 once it is not created by get all available devices. 0 means X_LINK_ANY_STATE, so I added that one to if condition and tested it with two cameras at the same time. It should be working fine now.

Copy link
Contributor

Choose a reason for hiding this comment

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

@zflat what was your execution command here ?

if(useWithIP) // Connecting to a camera with specific IP, requires static IP config beforehand
{
auto deviceInfo = dai::DeviceInfo(ipAddress);
if(deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
Copy link
Contributor

Choose a reason for hiding this comment

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

PoE device can be launched only if it is in Bootloader Mode I think. IIRC.

Copy link
Author

Choose a reason for hiding this comment

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

@saching13 I tested this with POE device too and sometimes it goes to X_LINK_ANY_STATE. Also, if you update the latest bootloader, it takes FLASH_BOOTED, so to be on the safe side, I included all the conditions, but if you think some of them is not necessary, then I will remove unnecessary ones.

Copy link
Contributor

Choose a reason for hiding this comment

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

is this the case ? @themarpe

Choose a reason for hiding this comment

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

XLink any state would be an issue querying the information from the device. We should fix that in core. Fo you have a repro @samialperen ?

Flash booted state happens when a pipeline is flashed onto device to run standalone on boot. That is a valid case to then stop that pipeline and start a new one

Copy link
Author

Choose a reason for hiding this comment

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

@themarpe @saching13 I have OAK-D version 1, OAK-D-PRO-W POE, OAK-D-PRO USB, OAK-D-PRO-W USB. If you can share more context about what is expected from each device (or device type USB vs poe), I can test this one and share the results here.

Choose a reason for hiding this comment

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

If queried you should see unbooted, bootloader, and booted if already running.
Check protocol for type of connection (usb/tcpip)

Comment on lines 386 to 388
} else {
device = std::make_shared<dai::Device>(pipeline, deviceInfo, usb2Mode);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

if(useWithIP)
section is already PoE region. you don't need to check for if PoE and else here. Do it only under MxID condition

Copy link
Author

Choose a reason for hiding this comment

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

Makes a lot of sense.

else if(useWithMxId) // Connecting to a camera with unique MxID
{
auto deviceInfo = dai::DeviceInfo(mxId);
if(deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
Copy link
Contributor

Choose a reason for hiding this comment

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

No need for Flashed_Boot here. it means device is running on it's own using the NOR flash config already.

Copy link
Author

Choose a reason for hiding this comment

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

I will test this if it works fine, then I will remove flash booted, but as far as I remember, flashed booted comes up once you update the bootloader.

Copy link
Contributor

Choose a reason for hiding this comment

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

thoughts ? @themarpe

Choose a reason for hiding this comment

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

@samialperen
Just updating the bootloader should not cause a flash booted state as described in the other comment. I assume you have a pipeline flashed on the device, which is then booted.

Also this code isn't valid. DeviceInfo is just a hokder of information that other functions fill out. Setting mxid to constructor doesn't fill out the state or any other fields.

Use Device.getX device to search for devices and return deviceinfo objects

Comment on lines 422 to 430
if(useWithIP) // Connecting to a camera with specific IP, requires static IP config beforehand
{
auto deviceInfo = dai::DeviceInfo(ipAddress);
if(deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
std::cout << "Device found with IP Address: " << ipAddress << std::endl;
if(poeMode) {
device = std::make_shared<dai::Device>(pipeline, deviceInfo);
} else {
device = std::make_shared<dai::Device>(pipeline, deviceInfo, usb2Mode);
Copy link
Contributor

Choose a reason for hiding this comment

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

same as above

Comment on lines 442 to 443
if(deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.state == X_LINK_UNBOOTED || deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
std::cout << "Connecting to device with MxID : " << mxId << std::endl;
Copy link
Contributor

Choose a reason for hiding this comment

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

same as above

throw std::runtime_error("\" DepthAI Device with MxId \"" + mxId + "\" is already booted on different process. \"");
if(useWithIP) // Connecting to a camera with specific IP, requires static IP config beforehand
{
auto deviceInfo = dai::DeviceInfo(ipAddress);
Copy link
Contributor

Choose a reason for hiding this comment

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

What will happen if useWithIp is set but ipAddress is not set ?
Same for useWithMxID

Copy link
Author

Choose a reason for hiding this comment

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

Good condition to check. will test and update it.

Copy link

@themarpe themarpe left a comment

Choose a reason for hiding this comment

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

As discussed in other comments main issue this PR has is that it assumes that DeviceInfo searches for the device. Just creating DeviceInfo object leaves everything else empty (default values, which due to opt. could be any value) and is likely the reason for seeing states such as any state, etc...

To handle this, retrieve a device list of available device using Device::getAvailableDevices() and then check if a specified deviceId or ipAddress/usbPort was found. If so, pass that specific DeviceInfo to the constructor of a Device

@themarpe
Copy link

CC: @Serafadam

@samialperen
Copy link
Author

As discussed in other comments main issue this PR has is that it assumes that DeviceInfo searches for the device. Just creating DeviceInfo object leaves everything else empty (default values, which due to opt. could be any value) and is likely the reason for seeing states such as any state, etc...

To handle this, retrieve a device list of available device using Device::getAvailableDevices() and then check if a specified deviceId or ipAddress/usbPort was found. If so, pass that specific DeviceInfo to the constructor of a Device

@themarpe this was my initial plan however, dai::DeviceInfo does not have a function to get IP address of the device. It only has deviceInfo.getMxId(). Would it be possible to update C++ API and add deviceInfo.getIPv4() function?

@zflat
Copy link

zflat commented Nov 18, 2022

@themarpe this was my initial plan however, dai::DeviceInfo does not have a function to get IP address of the device. It only has deviceInfo.getMxId(). Would it be possible to update C++ API and add deviceInfo.getIPv4() function?

I found that deviceInfo.name can be compared to an IP address string. Maybe this is not documented and only works in some cases? Or is this a supported way to check if a device has a specific IP address?

@themarpe
Copy link

@samialperen
Name carries ip or usb path depending on protocol. Its the current to go means if retrieving it.

@themarpe
Copy link

Specific functions to retrieve ipv4 could be added. You may open a PR against core

@samialperen
Copy link
Author

@themarpe I see. Lemme check deviceInfo.name, if it does not work out, I will open a PR for depthai-core. Thanks! I will keep updating here.

@saching13 saching13 changed the title Stereo inertial publisher node now supports a way to connect to indiv… Connect to a Specific Device using IP address as input Nov 28, 2022
… of all devices then iterate through them.
@themarpe
Copy link

themarpe commented Nov 28, 2022

Note I think this PR could greatly be simplified.

Core already supports the following: dai::Device(pipeline, dai::DeviceInfo("mxid_or_IP_or_USB_path"));
So redundancy on carrying over whether its IP or ID, etc... can be removed. And if the fields is unpopulated, you may just fall back to "automatic search" and thats it

And Device constructor also handles the devices's STATE so that can also be removed.

@samialperen
Copy link
Author

@themarpe I agree, the last commit was just to check whether everything is working or not.

Comment on lines 24 to 25
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

@iliabaranov
Copy link

+1 on this one, would make using multiple cameras (4 in our case :) ) much more reasonable.
Cheers!

@samialperen
Copy link
Author

+1 on this one, would make using multiple cameras (4 in our case :) ) much more reasonable. Cheers!

@iliabaranov good to know :) Sorry for the late reply. I hope it will be merged soon.
@saching13 @themarpe Let me know if something else is missing.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants