ros-drivers / rosserial

A ROS client library for small, embedded devices, such as Arduino. See: http://wiki.ros.org/rosserial
508 stars 526 forks source link

ESP32 + rosserial_python over WiFi: Lost sync with device #438

Closed sachin0x18 closed 4 years ago

sachin0x18 commented 4 years ago

Hi,

I am trying to establish rosserial communication between ESP32 (using ESP-IDF and not Arduino framework) and host Ubuntu machine. Here is my implementation: https://github.com/sachin0x18/rosserial_esp32

I am using ROS Kinetic and Ubuntu 16.04. rosserial_python version is 0.7.7 (as per package.xml).

I can establish communication over UART using rosrun rosserial_python serial_node.py and it can recognise publisher and subscriber topics.

When I establish communication over WiFi socket using rosrun rosserial_python serial_node.py tcp, rosserial_python on my Ubuntu machine can establish a connection and recognise the publisher and subscriber topics but after 15 seconds, it spits out Lost sync with device, restarting... and the same thing happens in a loop

[INFO] [1565188371.809821]: ROS Serial Python Node
Fork_server is:  False
[INFO] [1565188371.814939]: Waiting for socket connections on port 11411
waiting for socket connection
[INFO] [1565188380.808154]: Established a socket connection from 10.0.0.137 on port 49464
[INFO] [1565188380.809062]: calling startSerialClient
[INFO] [1565188382.986998]: Note: publish buffer size is 1024 bytes
[INFO] [1565188382.989866]: Setup publisher on chatter [std_msgs/String]
[ERROR] [1565188397.960632]: Lost sync with device, restarting...
[INFO] [1565188398.027021]: Setup publisher on chatter [std_msgs/String]
[ERROR] [1565188413.012285]: Lost sync with device, restarting...
[INFO] [1565188413.073520]: Setup publisher on chatter [std_msgs/String]

I am calling nh.spinOnce() every 1 second so it shouldn't be a problem of time sync failure. https://github.com/sachin0x18/rosserial_esp32/blob/master/src/examples/chatter/main/main.c

For debug purpose, I have dumped the bytes that I receive and bytes that I transmit

I (3645) event: sta ip: 10.0.0.137, mask: 255.255.254.0, gw: 10.0.0.1                                          
I (3645) wifi station: got ip:10.0.0.137
I (3645) wifi station: Connected to AP
I (3735) wifi station: Successfully connected
Received at read: 0xff
Received at read: 0xfe
Received at read: 0x0
Received at read: 0x0
Received at read: 0xff
Received at read: 0x0
Received at read: 0x0
Received at read: 0xff
I (5955) rosserial: Sending message over ROS 16
I (5965) Sent buffer: ff fe 08 00 f7 0a 00 00  00 00 00 00 00 00 00 f5     |................|
I (5965) rosserial: Sending message over ROS 80
I (5975) Sent buffer: ff fe 48 00 b7 00 00 7d  00 07 00 00 00 63 68 61     |..H....}.....cha|
I (5985) Sent buffer: 74 74 65 72 0f 00 00 00  73 74 64 5f 6d 73 67 73     |tter....std_msgs|
I (5995) Sent buffer: 2f 53 74 72 69 6e 67 20  00 00 00 39 39 32 63 65     |/String ...992ce|
I (6005) Sent buffer: 38 61 31 36 38 37 63 65  63 38 63 38 62 64 38 38    |8a1687cec8c8bd88|
I (6015) Sent buffer: 33 65 63 37 33 63 61 34  31 64 31 00 04 00 00 21     |3ec73ca41d1....!|
I (7025) rosserial: Sending message over ROS 24
I (7025) Sent buffer: ff fe 10 00 ef 7d 00 0c  00 00 00 68 65 6c 6c 6f       |.....}.....hello|
I (7025) Sent buffer: 20 77 6f 72 6c 64 21 f9                                | world!.|
Received at read: 0xff
Received at read: 0xfe
Received at read: 0x8
Received at read: 0x0
Received at read: 0xf7
Received at read: 0xa
Received at read: 0x0
Received at read: 0x6e
Received at read: 0xe6
Received at read: 0x4a
Received at read: 0x5d
Received at read: 0x98
Received at read: 0x1
Received at read: 0x9b
Received at read: 0x7
Received at read: 0xbf

I cannot seem to figure out what the problem is. I would really appreciate if somebody could help me out with this.

Thank you.

romainreignier commented 4 years ago

In your Github link, you only provide the serial (uart) version, could you provide the TCP over Wifi version please.

sachin0x18 commented 4 years ago

I have pushed the WiFi version on a separate branch (https://github.com/sachin0x18/rosserial_esp32/tree/feature/ros-over-tcp).

sachin0x18 commented 4 years ago

Did anyone get a chance to look into this ?

sachin0x18 commented 4 years ago

Setting the socket to non-blocking using fcntl solves this issue

fcntl(sock,F_SETFL,O_NONBLOCK);

noshluk2 commented 4 years ago

Setting the socket to non-blocking using fcntl solves this issue

fcntl(sock,F_SETFL,O_NONBLOCK);

explain please.. what you did there .. newbie here !

sachin0x18 commented 4 years ago

Sockets can be blocking or non-blocking. Performing read operation on blocking sockets results in socket waiting indefinitely till they receive the required length of data. It looks like rosserial expects non-blocking read/write. By default the sockets created in ESP32 are blocking type and in this case the read operation would block indefinitely and would not be able to call spinonce which resulted into Lost sync with device, restarting... (This is what my understanding is, I might be incorrect as well.)

So I just set the socket to non-blocking type using fcntl()

maker-ATOM commented 1 year ago

Setting the socket to non-blocking using fcntl solves this issue

fcntl(sock,F_SETFL,O_NONBLOCK);

where to add the function, in ESP32 firmware or the serial_node should be updated? if so what is the path of the python file, if not where exactly within the firmware should be added?