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

rospy.get_time() returns 0 when using gazebo

asked 2016-06-26 13:24:53 -0500

luketheduke gravatar image

Hi, When I run my code, I run into two problems. First, when I call rospy.get_time(), it returns 0. Secondly, in my while loop, perhaps due to the first issue, it only iterates once. Here is my code:

 #!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist

topicName = "cmd_vel_mux/teleop"

pub = rospy.Publisher("cmd_vel_mux/input/teleop", Twist, queue_size=10)
rospy.init_node('drive_time')




b_time = rospy.get_time()
print b_time
n = 0
while rospy.get_time() < b_time + 5:
    n+=1
    t = Twist()
    t.linear.x = 0.1
    pub.publish(t)
    rospy.sleep(0.1)
print n


print "done"
t = Twist()
t.linear.x = 0.1
pub.publish(t)

I am running a turtlebot in gazebo using turtlebot_world.launch. I tried changing the param use_sim_time to false and to true and it didn't work either way. When I initialize a node by typing it into the interpreter, rospy.get_time() works fine. Any ideas as to why this is happening?

edit retag flag offensive close merge delete

Comments

I am having the exact same problem. Any ideas?

pitosalas gravatar image pitosalas  ( 2018-08-19 06:44:09 -0500 )edit

Same problem. Anyone can help?

Kansai gravatar image Kansai  ( 2021-03-07 07:10:35 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2018-09-11 03:49:20 -0500

tfoote gravatar image

updated 2018-09-11 03:50:08 -0500

Time 0 means that your clock has not initialized yet. This will be returned until you receive a clock message from the simulator.

As recommended here: http://wiki.ros.org/Clock you should wait until the first non-zero value before doing any computations.

edit flag offensive delete link more

Comments

but the simulator is publishing clock!

Kansai gravatar image Kansai  ( 2021-03-07 07:07:32 -0500 )edit
0

answered 2018-09-11 06:06:08 -0500

ssg_1002 gravatar image

When use_sim_time rosparam is true, it uses the clock being published by the simulator. Hence it will return 0 till it receives any clock data from the simulator. Make sure that your Gazebo simulation is running i.e. not in paused state, in order to keep publishing time on /clock topic. For the while loop, you can try using the clock data being published by the simulator on the /clock topic.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2016-06-26 13:24:53 -0500

Seen: 878 times

Last updated: Sep 11 '18