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

Why isn't rospy.Rate.sleep() terminating?

asked 2013-08-30 13:49:03 -0500

obb gravatar image

updated 2014-01-31 13:46:31 -0500

tfoote gravatar image

Hi, I have written a python script which takes two tf frames and writes the transform between them to a file. The abbreviated code of the script looks like this:

listener = tf.TransformListener()
# waiting for first transform between origin and pose
listener.waitForTransform(origin, pose, rospy.Time(), rospy.Duration(5.0))
rate = rospy.Rate(10)
while not rospy.is_shutdown():
    try:
         now = rospy.Time.now()
         listener.waitForTransform(origin, pose, now, rospy.Duration(1.0))
         (trans, rot) = listener.lookupTransform(origin, pose, now)
         ... write trans and rot to the file ...
    # this exception is usually thrown when waitForTransform timed out
    except tf.Exception as e: 
         break # get out of the loop
    rate.sleep()
... some last commands before the script terminates ...

Usually this script should terminate when no more tf frames are published because I leave the loop when waitForTransform(...) throws an exception. When I run this code and start playing a bagfile (use_sim_time true and --clock) the script does not terminate because it gets stuck at rate.sleep() when rosbag play is finished. Any ideas why it behaves this way?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2013-09-01 05:21:59 -0500

dornhege gravatar image

updated 2013-09-01 05:23:01 -0500

rosbag play with --clock publishes time. That's the whole point of --clock. If the playback stops, ROS time will also stop and thus the rate never gets forward.

If the Rate is just supposed to happen every 0.1s to limit the loop (i.e. tied to the real world, not ROS time), you can use a WallRate instead (not sure if that exists in rospy)

edit flag offensive delete link more

Comments

This explanation makes sense. WallRate does not seem to exist in rospy. I guess I have to write my own sleep() method then...

obb gravatar image obb  ( 2013-09-02 05:34:36 -0500 )edit

You don't need your own sleep() method, just use time.sleep().

Martin Günther gravatar image Martin Günther  ( 2013-09-04 02:23:53 -0500 )edit
1

answered 2013-09-04 02:20:45 -0500

@dornhege's answer is correct. However, if all you want to do is execute some last commands when the node is killed (e.g., by pressing Ctrl-C), I think it's better to leave your code as it is and do something like this instead:

try:
    # ... your code
except rospy.ROSInterruptException:
    # ... some last commands before the node terminates

This feels cleaner than relying on a TF exception to tell you when "rosbag play has finished". (For instance, you'll also get TF exceptions before the transform you're looking for is published, not just after it has stopped publishing.)

Also, it's cleaner than relying on some relationship between ROS time and wall time. (You'll get into trouble when you pause your bag otherwise.)

If you don't like having to explicitly kill the node yourself, but rather have it exit when the bag ends, it's better to use the rosbag API explicitly (since you're already implementing some special behaviour for bags anyway).

edit flag offensive delete link more

Comments

I think the sleep is needed as there are some continuous things happening: "... write trans and rot to the file ...". However, everything you said is the right way of doing it.

dornhege gravatar image dornhege  ( 2013-09-04 03:26:03 -0500 )edit
1

You're right, maybe I didn't make myself clear. Of course the sleep is needed. I was trying to say that he can keep using rospy.sleep(), because I guess when there are no new transformations, he doesn't want to write anything to the file, so it's okay if the node "hangs" on sleep.

Martin Günther gravatar image Martin Günther  ( 2013-09-04 03:48:30 -0500 )edit

Oh yeah, that should be the standard way of any ROS node.

dornhege gravatar image dornhege  ( 2013-09-04 05:47:20 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-08-30 13:49:03 -0500

Seen: 5,583 times

Last updated: Sep 04 '13