[ros-users] Weird behavior when instantiating SimpleActionClient right after initializing node in rospy

Wim Meeussen meeussen at willowgarage.com
Mon Jun 20 16:58:17 UTC 2011


Chris,

> I ran into a problem when I ran python scripts where an actionlib
> action client is intantiated right after the node a the
> wait_for_server() function does not seem to work properly (it just
> does not wait).
[...]
> will return immediately with an error, even though I would expect it
> to wait 10s. If I uncomment rospy.sleep(1.0), everything works always
> as expected. Is there a more elegant solution to this?

I have an explanation for this behavior for the case where the
"use_sim_time" parameter is set to true.  A little background first:
when you run a node in simulated time, the node knows its time from
listening to messages on the /clock topic. When a node just starts up,
and it ask for rospy.Time.now() before the first message is received
on the /clock topic, the answer will be 0, because the node does not
yet know what the simulated time is.  Only once the node receives the
first message on the /clock topic will the node know the correct
simulated time. This means the time will at some point jump from 0 to
whatever the simulated time is.

So for your example with actionlib, the following happens: before the
node received a message on the /clock topic, you call waitt_for_server
with a timeout of 10 seconds. This call will remember the current time
(which will be 0 because no messages on /clock were received). Then it
will compute the time at which it should stop waiting for the server,
which will be 0+10 seconds. So whenever the time gets past 10 seconds,
the waiting will terminate. Then the next thing that happens is a
message comes in on the /clock topic, and tells the node the time is
something way past 10 seconds, and the waiting terminates almost
immediately.

When you put a sleep of any time larger than 0 seconds (you can sleep
for a few nanoseconds if you want) before the wait_for_server, the
node will be forced to wait for at least the first message on the
/clock topic, and your wait_for_server call will work as expected.

Hope this helps!

Wim

ps. Could you also post this question on answers.ros.org as a future
reference for other users?





-- 
--
Wim Meeussen
Willow Garage Inc.
<http://www.willowgarage.com)



More information about the ros-users mailing list