ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
8

rosserial lost sync with device

asked 2011-09-16 19:32:38 -0600

dan gravatar image

I occasionally get a lost sync message with rosserial: "Lost sync with device, restarting..." and am wondering what exactly is being restarted and how best to recover from that in the arduino code.

It seems that the python code is fine with starting while the arduino is running its loop(). So am I correct in interpreting that to mean the python code does not need to be running for the setup() part of the arduino code, the part where the initNode() statement as well as the advertise and subscribe statements occur?

I am driving a roomba with the arduino and it seems I most often get the "lost sync" when the roomba is taking its time getting some task completed. The python code does not recover from that. I tried putting in a statement to check if the connection was up: while (!nh.connected())...... but whenever it disconnected, it would just stay in this loop and never recover.

Suggestions?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
11

answered 2011-09-19 13:11:46 -0600

fergs gravatar image

There are a few steps in to sync/resync:

  1. On your Arduino, in setup(), you define what topics you want to publish/subscribe. This data is stored on the Arduino.

  2. When the python node (re)connects, it requests the topics to be published/subscribed from the Arduino.

  3. Once synced, both sides exchange data. The python node keeps track of when the last communication was, and if no communication has happened recently, it announces "Lost sync..." and attempts step 2 again to get the Arduino/PC back into a consistent state.

Even if you weren't publishing any information, the calls to spinOnce() will cause a timestamp update every 5s (which will keep the Arduino "synced" as far as the python node is concerned).

If you frequently see "Lost sync..." then you probably aren't calling spinOnce() frequently enough. You want to be careful, because this can also cause lots of data loss on subscribers (since your serial input buffers will only be processed when you call spinOnce()).

edit flag offensive delete link more

Comments

I was having frequent t lossync errors and this worked for me. There was a delay loop, which didn't contain any spinOnce() calls. Althought there was one before the delay, it wasnt frequent enough as you say. When I added a spinOnce() call inside the delay loop, problem was solved. Thank you

ebozgul gravatar image ebozgul  ( 2013-12-25 18:42:10 -0600 )edit

and what does "frequently enough" mean?

Kamiccolo gravatar image Kamiccolo  ( 2014-03-05 02:44:45 -0600 )edit

The time between each spinOnce calls should be less than a certain amount. However, I dont know the exact amount of that time. So if you are calling spinOnce but still experiencing "lost sync" error, the frequency of the spinOnce() calls might not be enough and you should call spinOnce() more often

ebozgul gravatar image ebozgul  ( 2014-03-09 23:01:48 -0600 )edit

how often spinOnce() that you mean?.. i gor confused with delay, rate in python and that spinOnce().. i just called spinOnce() in my loop like this:

void loop(){
  nh.spinOnce();
  delay(1);
}

is it not right?

adelleodel gravatar image adelleodel  ( 2016-06-04 07:09:59 -0600 )edit

Didn't work for me

أسامة الادريسي gravatar image أسامة الادريسي  ( 2017-11-04 04:52:06 -0600 )edit
0

answered 2022-06-08 04:53:41 -0600

I have this problem when using ROSSerial on stm32. After a lot of debugging I figured out that it was the UART transmit interrupt that was not called after a while running on the STM32. I never figured out why, since the device kept running all the other functionality, but I setup a watchdog timer for 0.5 s that is reset in the UART transmit callback. This is a partial fix as the device now is reset when it stops calling the callback and connection is resumed.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-09-16 19:32:38 -0600

Seen: 15,755 times

Last updated: Sep 19 '11