Closed sachin0x18 closed 4 years ago
In your Github link, you only provide the serial (uart) version, could you provide the TCP over Wifi version please.
I have pushed the WiFi version on a separate branch (https://github.com/sachin0x18/rosserial_esp32/tree/feature/ros-over-tcp).
Did anyone get a chance to look into this ?
Setting the socket to non-blocking using fcntl
solves this issue
fcntl(sock,F_SETFL,O_NONBLOCK);
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 !
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()
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?
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 outLost sync with device, restarting...
and the same thing happens in a loopI 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.cFor debug purpose, I have dumped the bytes that I receive and bytes that I transmit
I cannot seem to figure out what the problem is. I would really appreciate if somebody could help me out with this.
Thank you.