Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 import threading
00018
00019 import roslib; roslib.load_manifest('rosjava_benchmarks')
00020 import rospy
00021
00022 import tf.msg as tf_msgs
00023 import std_msgs.msg as std_msgs
00024
00025
00026 class PubsubBenchmark(object):
00027
00028 def __init__(self):
00029 self.count = itertools.count()
00030 self.time = rospy.Time.now()
00031 self.lock = threading.Lock()
00032
00033 def callback(self, _):
00034 with self.lock:
00035 self.count.next()
00036
00037 def run(self):
00038 tf_publisher = rospy.Publisher('tf', tf_msgs.tfMessage)
00039 status_publisher = rospy.Publisher('status', std_msgs.String)
00040 rospy.Subscriber('tf', tf_msgs.tfMessage, self.callback)
00041 while not rospy.is_shutdown():
00042 tf_publisher.publish(tf_msgs.tfMessage())
00043 if (rospy.Time.now() - self.time) > rospy.Duration(5):
00044 status_publisher.publish(std_msgs.String('%.2f Hz' % (self.count.next() / 5.0)))
00045 with self.lock:
00046 self.count = itertools.count()
00047 self.time = rospy.Time.now()
00048
00049
00050 if __name__ == '__main__':
00051 try:
00052 rospy.init_node('benchmark')
00053 PubsubBenchmark().run()
00054 except rospy.ROSInterruptException:
00055 pass