Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called.
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)
Whats wrong?
Update 1: backtrace
(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 ()
This looks like something doesn't fit: The error looks like it's from a c++ binary.
@dornhege, You are right, the problem is in the tf2 C++ library. I have added the backtrace.
Any news about this? I've run into the same error.