dbm_param.py
Go to the documentation of this file.
00001 import rospy
00002 
00003 class DBMParam:
00004         @staticmethod
00005         def create_params(topic_name, min_frequency, max_frequency, default_frequency):
00006                 DBMParam.__add_managed_topic(topic_name)
00007                 DBMParam.__add_frequency(topic_name, default_frequency)
00008                 DBMParam.__add_min_frequency(topic_name, min_frequency)
00009                 DBMParam.__add_max_frequency(topic_name, max_frequency)
00010                 DBMParam.__add_priority(topic_name)
00011                 DBMParam.__add_message_size(topic_name)
00012                 DBMParam.__add_max_bandwidth()
00013                 DBMParam.__add_max_bandwidth_utilization()
00014                 DBMParam.__add_optimization_rate()
00015                 DBMParam.__add_manage_local_subscribers()
00016 
00017         @staticmethod
00018         def __add_managed_topic(topic_name):
00019                 param_name = "/dbm/topics"
00020                 managedTopics = rospy.get_param(param_name, {})
00021                 if topic_name not in managedTopics:
00022                         managedTopics[topic_name] = 0
00023                         rospy.set_param(param_name, managedTopics)
00024 
00025         @staticmethod
00026         def __add_frequency(topic_name, default_frequency):
00027                 param_name = topic_name + "/dbm/frequency/current_value"
00028                 if not rospy.has_param(param_name):
00029                         rospy.set_param(param_name, default_frequency)
00030 
00031         @staticmethod
00032         def __add_min_frequency(topic_name, min_frequency):
00033                 param_name = topic_name + "/dbm/frequency/min"
00034                 if not rospy.has_param(param_name):
00035                         rospy.set_param(param_name, min_frequency)
00036 
00037         @staticmethod
00038         def __add_max_frequency(topic_name, max_frequency):
00039                 param_name = topic_name + "/dbm/frequency/max"
00040                 if not rospy.has_param(param_name):
00041                         rospy.set_param(param_name, max_frequency)
00042 
00043         @staticmethod
00044         def __add_priority(topic_name):
00045                 param_name = topic_name + "/dbm/priority"
00046                 if not rospy.has_param(param_name):
00047                         rospy.set_param(param_name, 1.0)
00048 
00049         @staticmethod
00050         def __add_message_size(topic_name):
00051                 param_name = topic_name + "/dbm/message_size_in_bytes"
00052                 if not rospy.has_param(param_name):
00053                         rospy.set_param(param_name, 0.0)
00054 
00055         @staticmethod
00056         def __add_max_bandwidth():
00057                 param_name = "/dbm/max_bandwidth_in_mbit"
00058                 if not rospy.has_param(param_name):
00059                         rospy.set_param(param_name, 10.0)
00060 
00061         @staticmethod
00062         def __add_max_bandwidth_utilization():
00063                 param_name = "/dbm/max_bandwidth_utilization"
00064                 if not rospy.has_param(param_name):
00065                         rospy.set_param(param_name, 1)
00066 
00067         @staticmethod
00068         def __add_optimization_rate():
00069                 param_name = "/dbm/optimization_rate"
00070                 if not rospy.has_param(param_name):
00071                         rospy.set_param(param_name, 1)
00072 
00073         @staticmethod
00074         def __add_manage_local_subscribers():
00075                 param_name = "/dbm/manage_local_subscribers"
00076                 if not rospy.has_param(param_name):
00077                         rospy.set_param(param_name, False)
00078 
00079         @staticmethod
00080         def get_current_frequency(topic_name):
00081                 param_name = topic_name + "/dbm/frequency/current_value"
00082                 if rospy.has_param(param_name):
00083                         return rospy.get_param(param_name)
00084                 else:
00085                         return 0
00086 
00087         @staticmethod
00088         def set_current_frequency(topic_name, frequency):
00089                 param_name = topic_name + "/dbm/frequency/current_value"
00090                 rospy.set_param(param_name, frequency)
00091 
00092         @staticmethod
00093         def get_min_frequency(topic_name):
00094                 param_name = topic_name + "/dbm/frequency/min"
00095                 if rospy.has_param(param_name):
00096                         return rospy.get_param(param_name)
00097                 else:
00098                         return 0
00099 
00100         @staticmethod
00101         def get_max_frequency(topic_name):
00102                 param_name = topic_name + "/dbm/frequency/max"
00103                 if rospy.has_param(param_name):
00104                         return rospy.get_param(param_name)
00105                 else:
00106                         return 0
00107 
00108         @staticmethod
00109         def get_priority(topic_name):
00110                 param_name = topic_name + "/dbm/priority"
00111                 if rospy.has_param(param_name):
00112                         return rospy.get_param(param_name)
00113                 else:
00114                         return 0
00115 
00116         @staticmethod
00117         def get_message_size_in_bytes(topic_name):
00118                 param_name = topic_name + "/dbm/message_size_in_bytes"
00119                 if rospy.has_param(param_name):
00120                         return rospy.get_param(param_name)
00121                 else:
00122                         return 0
00123 
00124         @staticmethod
00125         def set_message_size_in_bytes(topic_name, size):
00126                 param_name = topic_name + "/dbm/message_size_in_bytes"
00127                 rospy.set_param(param_name, size)
00128 
00129         @staticmethod
00130         def get_max_bandwidth_in_mbits():
00131                 param_name = "/dbm/max_bandwidth_in_mbit"
00132                 if rospy.has_param(param_name):
00133                         return rospy.get_param(param_name)
00134                 else:
00135                         return 0
00136 
00137         @staticmethod
00138         def get_max_bandwidth_utilization():
00139                 param_name = "dbm/max_bandwidth_utilization"
00140                 if rospy.has_param(param_name):
00141                         return rospy.get_param(param_name)
00142                 else:
00143                         return 0
00144 
00145         @staticmethod
00146         def get_managed_topics():
00147                 param_name = "dbm/topics"
00148                 if rospy.has_param(param_name):
00149                         return [topic for topic, isManaged in rospy.get_param(param_name).iteritems() if isManaged == 1]
00150                 else:
00151                         return []


dynamic_bandwidth_manager
Author(s): Ricardo Emerson Julio , Guilherme Sousa Bastos
autogenerated on Mon Sep 14 2015 07:35:27