Go to the documentation of this file.00001 import rospy
00002 from .dbm_param import DBMParam
00003
00004 class DBMRate(rospy.Rate):
00005 def __init__(self, publisher, min_frequency, max_frequency, default_frequency = None):
00006 if default_frequency is None:
00007 default_frequency = max_frequency
00008
00009 self.topic_name = publisher.name
00010 self.default_frequency = default_frequency
00011 DBMParam.create_params(self.topic_name, min_frequency, max_frequency, default_frequency)
00012 rospy.Rate.__init__(self, default_frequency)
00013
00014 def sleep(self):
00015 current_frequency = DBMParam.get_current_frequency(self.topic_name)
00016 if current_frequency == 0:
00017 current_frequency = self.default_frequency
00018 self.sleep_dur = rospy.rostime.Duration(0, int(1e9/current_frequency))
00019 super(DBMRate, self).sleep()