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

Can't connect to Inertial+ with ros2 driver #11

Open
HamRadioDXer opened this issue May 7, 2022 · 16 comments
Open

Can't connect to Inertial+ with ros2 driver #11

HamRadioDXer opened this issue May 7, 2022 · 16 comments

Comments

@HamRadioDXer
Copy link

HamRadioDXer commented May 7, 2022

I have the same problem as this,but we not running in docker

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [oxts_driver-1]: process started with pid [8051]
[INFO] [oxts_ins-2]: process started with pid [8053]
[oxts_driver-1] [INFO] [1651887087.148714540] [oxts_driver]: Connecting: 192.168.1.156:3000
[oxts_driver-1] [INFO] [1651887087.148762504] [oxts_driver]: Waiting for INS config information...

we runs normally under ROS1 driver

@ljones-oxts
Copy link
Contributor

ljones-oxts commented May 9, 2022

Hello,

The usual culprit for these errors are IP configurations. In a terminal window, could you issue the ifconfig command to see what your machine's IP address is.

Example output (the IP address that we need looks like inet 192.168.xxx.xxx under the first ethernet interface ens33:


ros-user@ubuntu:~$ ifconfig
ens33: flags=4163<UP,BROADCAST,RUNNING,MULTICAST>  mtu 1500
        inet 192.168.xxx.xxx  netmask 255.255.255.0  broadcast xxx.xxx.xxx.255
        inet6 0000::0000:0000:0000:0000  prefixlen 64  scopeid 0x20<link>
        ether 00:00:00:00:00:db  txqueuelen 1000  (Ethernet)
        RX packets 337141  bytes 288821637 (288.8 MB)
        RX errors 0  dropped 0  overruns 0  frame 0
        TX packets 634121  bytes 157870197 (157.8 MB)
        TX errors 0  dropped 0 overruns 0  carrier 0  collisions 0

lo: flags=73<UP,LOOPBACK,RUNNING>  mtu 65536
        inet 127.0.0.1  netmask 255.0.0.0
        inet6 ::1  prefixlen 128  scopeid 0x10<host>
        loop  txqueuelen 1000  (Local Loopback)
        RX packets 457388  bytes 123078281 (123.0 MB)
        RX errors 0  dropped 0  overruns 0  frame 0
        TX packets 457388  bytes 123078281 (123.0 MB)
        TX errors 0  dropped 0 overruns 0  carrier 0  collisions 0

It is essential that the IPv4 address of your machine be on the same subnet as your INS (in your case, it should be of the form 192.168.1.xxx).

Thanks

Llyr

@ZYblend
Copy link

ZYblend commented Jul 18, 2022

I got the same issue but the subnets are matched. unit_ip: 195.0.0.94, machine ip:195.0.0.22, 255.255.255.0.

I tried runing both in docker container (ros galactic) and ubuntu machine (ros foxy), got the same issue.

The unit could be accessed through GUI software but could not be accessed through ros interface.

@ljones-oxts
Copy link
Contributor

Hello

Can you first verify that the output of ifconfig command is as you would expect?

We would expect an entry which looks like inet 195.0.0.22 netmask 255.255.255.0 broadcast 195.0.0.255 on the main network interface. If you can also show us the flags of that particular network interface, that would also be helpful.

Thanks

Llyr

@ZYblend
Copy link

ZYblend commented Jul 21, 2022

Hello

Can you first verify that the output of ifconfig command is as you would expect?

We would expect an entry which looks like inet 195.0.0.22 netmask 255.255.255.0 broadcast 195.0.0.255 on the main network interface. If you can also show us the flags of that particular network interface, that would also be helpful.

Thanks

Llyr

Thanks for replying,

We checked the output of ifconfig. It is same as what we expected.
image

We have a new finding:
We printed the statement sender_endpoint (showed 195.0.0.94:3000) and required_sender_endpoint (showed 195.0.0.94:5001) in the line.
So it is not matched, but we did not receive any error message. Then we tried to change the port in default.yaml to 5001. The program is blocked somewhere again and the statements were not printed. Then we removed the expression in that while loop, we could get some data. But we are not sure if it is a good modification.

@schroettinger
Copy link

Then we removed the expression in that while loop, we could get some data. But we are not sure if it is a good modification.

What exactly was your change?

I face a similar problem: I can set up the IP address as demanded and compile/start the node with the proper IP/Port, but after starting the component it also stops at:

[oxts_driver-1] [INFO] [1676281947.940964336] [oxts_driver]: Connecting: 195.0.0.22:3000
[oxts_driver-1] [INFO] [1676281947.941088350] [oxts_driver]: Waiting for INS config information...

Gonna try to debug sender_endpoint and required_sender_endpoint, let's see.

Btw: I use Ubuntu 20.04 and dockerized this:

# Take ROS2 galactic as base image
FROM ros:galactic

# Set up a usable shell
SHELL ["/bin/bash", "-c"]

# WORKDIR is defined as app - can be set as argument maybe
WORKDIR /app

# update and install all neccessary software packages
RUN apt-get update 
#RUN apt-get upgrade -y
RUN apt-get install -y \
	libboost-all-dev

# Copy the software component to the image
COPY ./oxts_ros2_driver ./oxts_ros2_driver

# source the ROS environment for building && build with colcon
RUN source "/opt/ros/galactic/setup.bash" && colcon build

# The entrypoint script shall execute the sorucing for the newly build package
# In order to do so the last line of the ros_entrypoint.sh script (exec "$@") is excanged with 
# the source command and the exec.. cmd itself again:
RUN sed -i "s/exec \"\$\@\"/source \/app\/install\/setup.bash\n\exec \"\$\@\"/g" /ros_entrypoint.sh

# add a user to not run everything as root (host mitigation possible otherwise)
RUN useradd --create-home -ms /bin/bash user  
#RUN usermod -a -G adm user
USER user

# Execute the node with the ros2 launch command
CMD ["ros2","launch","oxts","run.py","unit_ip:=195.0.0.22"]

...starting it with...

sudo docker run --rm -it --name node_oxts --network=host oxts_ros2_driver:1.0

A short investigation with wireshark also showed me, that the UDP packages are send from the GNSS and avaialble on the network.

(Note: used same IP address as in previous posts)

@ljones-oxts
Copy link
Contributor

Hi @ZYblend and @schroettinger

The while loop being referenced is likely on lines 159-161 of src/oxts/oxts_driver/include/oxts_driver/driver.hpp:


while (nrx->mSerialNumber == 0 || nrx->mIsImu2VehHeadingValid == 0) {
   (*this.*update_ncom)();
}

The driver is waiting until it has received valid configuration data. This tells me that the driver is not receiving packets on the given IP address and port combination.

@ZYblend : The required_sender_endpoint should be being populated from your default.yaml file - thus the correct value for unit_port should be 3000. At what point did your application then hang?

@schroettinger : For your issue, what is the Sender IP for those UDP packets according to Wireshark?

Thanks

Llyr

@schroettinger
Copy link

Hi Llyr,
see following image about what I get from wireshark:
image

This is my little debugging by now:

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [oxts_driver-1]: process started with pid [6102]
[INFO] [oxts_ins-2]: process started with pid [6104]
[oxts_driver-1] [INFO] [1676298335.177186359] [oxts_driver]: Connecting: 195.0.0.52:3000
[oxts_driver-1] [INFO] [1676298335.177292523] [oxts_driver]: Waiting for INS config information...
[oxts_driver-1] 0 //<---- this is nrx->mSerialNumber from driver.h
[oxts_driver-1] required_sender_endpoint - 195.0.0.52:3000 //<---- from udp_server_client.h, receive_from() function
[oxts_driver-1] sender_endpoint - 0.0.0.0:0

thx & br
schroettinger

@ljones-oxts
Copy link
Contributor

Hi @schroettinger

Many thanks for the information. I'm concerned at the 0.0.0.0:0 value for sender_endpoint: can you confirm whether you output that before or after the call to socket.receive_from(), inside the while loop on line 93 of udp_server_client.h?

Thanks

Llyr

@schroettinger
Copy link

Hi @ljones-oxts

This is how I gathered the information:
image

thx & br
schroettinger

@ljones-oxts
Copy link
Contributor

Hi @schroettinger

Can you put the line std::cout << "sender_endpoint - " << sender_endpoint << std::endl on the line before the while condition instead? sender_endpoint is supposed to be zero until the call to socket.receive_from() - it is this function which populates the sender_endpoint from information is has been given from the UDP datagram.

Thanks

Llyr

@schroettinger
Copy link

Hi @ljones-oxts

I did as you suggested:

image

with starting it with ros2 launch oxts run.py unit_ip:=195.0.0.52 unit_port:=3000

image

result:
[oxts_driver-1] sender_endpoint - 195.0.0.52:5001
and
required_sender_endpoint - 195.0.0.52:3000.

Means it stays in the while, as the values are not the same. But they should fit somewhen in order to go further and return the received_bytes, right? Or is it supposed to stay in the while loop?

The GNSS is ping-able:
image

One question regarding my wireshark image: port 3000 is the right one to choose, or?

Many thanks in advance!
schroettinger

@ljones-oxts
Copy link
Contributor

Hi @schroettinger

I've had a chat with a colleague of mine and we think this may be due to a proxy situation (the fact that the sender/destination ports get mapped from 5001 to 3000 is a clue to this).

This is subsequently causing issues because the code is trying to find a packet with a sender IP:port as 195.0.0.52:3000 (rather than 195.0.0.52:5001). Changing the unit's port in the YAML file isn't going to help either, because the correct local port to bind to is indeed 3000.

Thus, to fix your issue in the short term, can you try changing line 138-140 in src/oxts/oxts_driver/include/oxts_driver/driver.hpp:

From:


unitEndpointNCom = boost::asio::ip::udp::endpoint(
     boost::asio::ip::address::from_string(this->unit_ip),
     this->unit_port);

To:


unitEndpointNCom = boost::asio::ip::udp::endpoint(
     boost::asio::ip::address::from_string(this->unit_ip),
     5001);

Once we ascertain that this indeed fixes your scenario, I can then try and put something together on our side for a more permanent solution which supports this scenario.

Thanks

Llyr

@schroettinger
Copy link

Hi @ljones-oxts

That worked out! 🥳

image

I can see all the ROS2 messages send out properly!
MANY thanks, you made my day!

Best regards
schroettinger

@ljones-oxts
Copy link
Contributor

Hi @schroettinger

Glad it worked for you!

@ZYblend Could you try applying the same fix to see if it works for you?

Thanks

Llyr

@HiroshiYasuda-TRI
Copy link

@ljones-oxts Thank you for the information.
I had the same issue with my RT4000, and the workaround worked for me as well.
Do you know why this (sender port being 5001) happens? Is there a configuration of the device?
I have an almost identical setup with RT3000, and it does not have this problem.

@jhallett-oxts
Copy link
Collaborator

Hi @HiroshiYasuda-TRI, I'm a colleague of @ljones-oxts.

I had a little look into this, I suspect why this occurs is because some older units like the RT4000 and the inertial+ run on different type of firmware than the newer units. In some cases specific firmware versions have a fixed local port. It would useful to know what specific firmware your units (both the RT4000 and RT3000) are running just so I can check to see if that it is the case with your unit.

It is worth noting that these units have reached their product end of life so there isn't any new firmware available (hence spending sometime digging to find the route cause of this issue).

On the ROS2 driver end, when we understand where this issue is coming from, we can look to address this use case it in future updates.

All the best,

Joe

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

No branches or pull requests

6 participants