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

Address family is not supported by protocol #185

Closed
civerachb-cpr opened this issue Sep 24, 2020 · 3 comments
Closed

Address family is not supported by protocol #185

civerachb-cpr opened this issue Sep 24, 2020 · 3 comments

Comments

@civerachb-cpr
Copy link

civerachb-cpr commented Sep 24, 2020

I'm having problems getting an OS-1 installed on my robot. I can launch the node from my laptop (x64, Ubuntu 18.04 + ROS Melodic) just fine. But when I launch it from the robot's internal PC (also x64, Ubuntu 18.04 + ROS Melodic) I get the following output:

$ roslaunch ouster_ros os1.launch os1_hostname:=192.168.131.20 os1_udp_dest:=192.168.131.1
... logging to /home/administrator/.ros/log/816139dc-fe7b-11ea-b3e7-00301804b660/roslaunch-cpr-a200-0627-6161.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://cpr-a200-0627:35041/

SUMMARY
========

PARAMETERS
 * /os1_cloud_node/tf_prefix: 
 * /os1_node/lidar_mode: 
 * /os1_node/metadata: 
 * /os1_node/os1_hostname: 192.168.131.20
 * /os1_node/os1_imu_port: 0
 * /os1_node/os1_lidar_port: 0
 * /os1_node/os1_udp_dest: 192.168.131.1
 * /os1_node/replay: False
 * /os1_node/timestamp_mode: 
 * /rosdistro: melodic
 * /rosversion: 1.14.9

NODES
  /
    os1_cloud_node (ouster_ros/os1_cloud_node)
    os1_node (ouster_ros/os1_node)

auto-starting new master
process[master]: started with pid [6178]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 816139dc-fe7b-11ea-b3e7-00301804b660
process[rosout-1]: started with pid [6197]
started core service [/rosout]
process[os1_node-2]: started with pid [6206]
process[os1_cloud_node-3]: started with pid [6210]
[ INFO] [1600961700.011039874]: Connecting to sensor at 192.168.131.20...
[ INFO] [1600961700.011630019]: Sending data to 192.168.131.1 using lidar_mode: 1024x10
udp socket(): Address family not supported by protocol
udp socket(): Address family not supported by protocol
[ERROR] [1600961700.013319222]: Failed to initialize sensor at: 192.168.131.20
[ INFO] [1600961700.015419916]: waitForService: Service [/os1_node/os1_config] has not been advertised, waiting...
================================================================================REQUIRED process [os1_node-2] has died!
process has died [pid 6206, exit code 1, cmd /home/administrator/catkin_ws/devel/lib/ouster_ros/os1_node __name:=os1_node __log:=/home/administrator/.ros/log/816139dc-fe7b-11ea-b3e7-00301804b660/os1_node-2.log].
log file: /home/administrator/.ros/log/816139dc-fe7b-11ea-b3e7-00301804b660/os1_node-2*.log
Initiating shutdown!
================================================================================
[os1_cloud_node-3] killing on exit
[os1_node-2] killing on exit
[rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Checking the diagnostics through the web interface, I see messages like this:

    {
        "active": true,
        "category": "UDP_TRANSMISSION",
        "cursor": 15,
        "id": "0x01000015",
        "level": "WARNING",
        "msg": "Client not reachable on lidar data port; check udp_ip, udp_port_lidar, and client machine.",
        "msg_verbose": "Failed to send lidar UDP data to destination host 192.168.131.1:53999",
        "realtime": "9849970313137"
      },

Obviously there appears to be a problem establishing the UDP connection, but I can't figure out what's causing the issue. There are no iptables rules that should be blocking the connection. I can ping the sensor on its static IP address, and the main PC responds to pings. Running netcat -u -z -v 192.168.131.1 53000-53999 doesn't show any of the connections being refused.

I've tried using a physical ethernet port on the PC, as well as a USB3-to-ethernet dongle (just in case it was a problem with the networking hardware itself), all with the same results. If I connect my laptop into the robot's internal network and launch the node from my laptop it works just fine; the problem appears specific to the robot's internal PC. Using the exact same USB3-to-ethernet dongle plugged into my laptop works, but connecting it to a USB3 port on the robot give the same error(s) as above.

I'm scratching my head trying to figure out what the missing piece of the puzzle is. Any suggestions on what I'm missing to get the lidar node started on my robot?

@civerachb-cpr
Copy link
Author

Turns out that IPv6 must be enabled for the sensor to work. Enabling that in the kernel appears to have fixed the problem.

@robokamran
Copy link

I had the same problem BUT, since I had to use only IPV4 on my system (to maximize my network performance and avoid double-routing issues on ROS) I edited the code to only use IPV4 like a normal and reasonable sensor 😎.
So, go to file client.cpp change line 68 to this: hints.ai_family = AF_INET; and comment out the following whole block from line 93-100:

// int off = 0;
// if (setsockopt(sock_fd, IPPROTO_IPV6, IPV6_V6ONLY, (char*)&off,
//                sizeof(off))) {
//     std::cerr << "udp setsockopt(): " << impl::socket_get_error()
//               << std::endl;
//     impl::socket_close(sock_fd);
//     return SOCKET_ERROR;
// }

compile and run and enjoy not having to use IPV6!

@Sollimann
Copy link

@robokamran I had the same issue running this on the Clearpath Jackal Intel NuC computer. The NuC had disabled IPv6 in GRUB bootloader /etc/default/grub by default.

Your two fixes worked! 💯

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

3 participants