Skip to content

Instantly share code, notes, and snippets.

@tfoote
Last active February 14, 2017 00:41
Show Gist options
  • Save tfoote/d3066846abfd6fc40f47b005a8a9dad4 to your computer and use it in GitHub Desktop.
Save tfoote/d3066846abfd6fc40f47b005a8a9dad4 to your computer and use it in GitHub Desktop.
#!/usr/bin/env python
# A simple script to print the realtime factor under simulated time.
import time
import rospy
from rosgraph_msgs.msg import Clock
last_wall_time = time.time()
last_clock_time = rospy.Time(0)
def callback(data):
global last_wall_time
global last_clock_time
current_wall = time.time()
wall_elapsed = current_wall - last_wall_time
clock_elapsed = data.clock - last_clock_time
if wall_elapsed < 1.0:
return
realtime_factor = clock_elapsed.to_sec()/wall_elapsed
rospy.loginfo("Realtime Factor: %s" % (realtime_factor))
last_wall_time = current_wall
last_clock_time = data.clock
rospy.init_node('realtime_factor', anonymous=True)
rospy.Subscriber('/clock', Clock, callback)
rospy.spin()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment