Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. #30

Closed
liborw opened this issue Aug 22, 2013 · 18 comments
Assignees
Labels

Comments

@liborw
Copy link

liborw commented Aug 22, 2013

Under Hydro the following minimal example

#!/usr/bin/env python

import roslib; roslib.load_manifest('sandbox')
import rospy
import tf

if __name__ == '__main__':
    rospy.init_node("test_tf_listener")
    listener = tf.TransformListener()
    (trans, rot) = listener.waitForTransform('test_1', 'test_2', rospy.Time(0), rospy.Duration(0))

result in this error:

$ rosrun sandbox test_tf_listener.py 
terminate called after throwing an instance of 'ros::TimeNotInitializedException'
  what():  Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called.  If this is a standalone app or test that just uses ros::Time and does not communicate over ROS, you may also call ros::Time::init()
Aborted (core dumped)
@liborw
Copy link
Author

liborw commented Aug 22, 2013

I have tried it in gdb and this is the back trace:

(gdb) bt
#0  0x00007ffff68e1425 in raise () from /lib/x86_64-linux-gnu/libc.so.6
#1  0x00007ffff68e4b8b in abort () from /lib/x86_64-linux-gnu/libc.so.6
#2  0x00007ffff34c069d in __gnu_cxx::__verbose_terminate_handler() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#3  0x00007ffff34be846 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#4  0x00007ffff34be873 in std::terminate() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#5  0x00007ffff34be96e in __cxa_throw () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#6  0x00007ffff41777d4 in ros::Time::now() () from /opt/ros/hydro/lib/librostime.so
#7  0x00007ffff397714c in tf2_ros::Buffer::canTransform(std::string const&, std::string const&, ros::Time const&, ros::Duration, std::string*) const ()
   from /opt/ros/hydro/lib/libtf2_ros.so
#8  0x00007ffff4ae6aea in tf::Transformer::waitForTransform(std::string const&, std::string const&, ros::Time const&, ros::Duration const&, ros::Duration const&, std::string*) const () from /opt/ros/hydro/lib/python2.7/dist-packages/tf/_tf.so
#9  0x00007ffff4adac99 in ?? () from /opt/ros/hydro/lib/python2.7/dist-packages/tf/_tf.so
#10 0x0000000000466254 in PyEval_EvalFrameEx ()
#11 0x000000000057bd02 in PyEval_EvalCodeEx ()
#12 0x000000000057c77d in PyRun_FileExFlags ()
#13 0x000000000057e4a1 in PyRun_SimpleFileExFlags ()
#14 0x0000000000512cfd in Py_Main ()
#15 0x00007ffff68cc76d in __libc_start_main () from /lib/x86_64-linux-gnu/libc.so.6
#16 0x000000000041ba51 in _start ()

So it looks that the tf is using tf2 and the problem is somewhere there.

@tfoote
Copy link
Member

tfoote commented Aug 26, 2013

This is a reoccurance of this patched issue: 70defb1

@tfoote
Copy link
Member

tfoote commented Aug 27, 2013

The cleaner solution is to use the python tf2 buffer class.

@tfoote
Copy link
Member

tfoote commented Aug 28, 2013

Actually a problem in tf2_ros fixed here: ros/geometry2@5e41627

@tfoote tfoote closed this as completed Aug 28, 2013
@liborw
Copy link
Author

liborw commented Sep 3, 2013

Can You post a simple example how to get transformation from the tf2, I have tried all tutorial I could found and none of the worked.

@jonbinney
Copy link

@liborw not sure if you still need this, but here's a simple example for tf2 in python:

#!/usr/bin/env python                                                                                                                                                                                                                                                                  
import sys
import rospy
import math
import tf2_ros
import turtlesim.msg
import turtlesim.srv

rospy.init_node('tf_turtle')

buf = tf2_ros.Buffer()
listener = tf2_ros.TransformListener(buf)

# wait a second for frames to accumulate. buf.lookup_transform seems to fail immediately if it hasn't yet                                                                                                                                                                              
# gotten any transfroms for the 'odom' frame, instead of waiting for the timeout                                                                                                                                                                                                       
rospy.sleep(1.0)

try:
    tform = buf.lookup_transform('odom', 'base_link', rospy.Time(0), timeout=rospy.Duration(4))
except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException) as e:
    print e

print 'Success'
print tform

@liborw
Copy link
Author

liborw commented Oct 25, 2013

This helps a bit but what I missing is wait for transform.

@jonbinney
Copy link

From my understanding, that should now be built into lookup_transform, which is why the "timeout" arg is passed in.

@liborw
Copy link
Author

liborw commented Oct 30, 2013

However, this probably still doesn't work:

This is the call:

tform = self.tfb.lookup_transform(source_frame, target_frame, stamp, timeout=rospy.Duration(10))

And the error:

Lookup would require extrapolation into the future.  Requested time 1383123031.108603954 but the latest data is at time 1383123031.101570845, when looking up transform from frame [a] to frame [b]

@jonbinney
Copy link

Yeah i've had that problem too. Seemed like a bug to me

@jdddog
Copy link

jdddog commented Nov 1, 2013

Is there a fix for this that doesn't involve shifting to tf2?

tfoote added a commit that referenced this issue Nov 4, 2013
…imeNotInitializedException. This will at least let things function, there are still issues with simtime not propogating inside correctly. fixes #30
tfoote added a commit to ros/geometry2 that referenced this issue Nov 4, 2013
@tfoote
Copy link
Member

tfoote commented Nov 4, 2013

There was a second issue with the sleep failing due to being uninitialized.

I believe that I have fixed the issue here: 0a034c5 Can someone verify that this works for them? You will need to checkout geometry_experimental into your workspace from geometry_issue_30 branch.

@tfoote tfoote reopened this Nov 4, 2013
@jdddog
Copy link

jdddog commented Nov 12, 2013

Awesome, it works for me, thanks for fixing it!

The code at the very top wont work fyi, because waitForTransform returns None. So I tested it with this:

#!/usr/bin/env python

import roslib; roslib.load_manifest('beginner_tutorials')
import rospy
import tf
import sys, traceback

if __name__ == '__main__':
    rospy.init_node("test_tf_listener")
    listener = tf.TransformListener()

    try:
        listener.waitForTransform('camera_link', 'camera_rgb_frame', rospy.Time(), rospy.Duration(5.0))
        (trans, rot) = listener.lookupTransform('camera_link', 'camera_rgb_frame', rospy.Time())
        print str(trans) + " " + str(rot)
    except:        
        traceback.print_exc(file=sys.stdout)

@tompe17
Copy link

tompe17 commented Nov 13, 2013

I got bitten by the same bug and i do not want to convert to tf2 now. So will the fix above be available soon in hydro? Or do I need to check out the branch?

@tfoote
Copy link
Member

tfoote commented Nov 13, 2013

This change is in 0.4.8 It's available in the testing debian repo at the moment, but has not been synced to the public repo: http://www.ros.org/debbuild/hydro.html?q=geometry_experimental

A sync can be expected in the next week or so. We've had a pattern of syncing approximately every 2 weeks.

@tfoote tfoote closed this as completed Dec 27, 2013
@loulansuiye
Copy link

terminate called after throwing an instance of 'ros::TimeNotInitializedException'
what(): Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. If this is a standalone app or test that just uses ros::Time and does not communicate over ROS, you may also call ros::Time::init()
Aborted (core dumped)

@loulansuiye
Copy link

when I use roscpp function ros::init(argc,argv,"name") ,it report the up problem

@tfoote
Copy link
Member

tfoote commented Aug 24, 2018

@loulansuiye This is a years closed issue for a completely different component in a different language. If you'd like some help please ask a question on answers.ros.org

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

6 participants