default_optimizer.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import dynamic_bandwidth_manager
00005 import pulp
00006 import numpy as np
00007 
00008 def optimize(managed_topics):
00009     # Initialize the model
00010     model = pulp.LpProblem("Dynamic Bandwidth Optmization for Multirobot Systems", pulp.LpMaximize)
00011 
00012     # Create a dictionary of pulp variables with keys from managed topics
00013     # the default lower bound is -inf
00014     f = pulp.LpVariable.dict('f_%s', managed_topics, lowBound=0)
00015 
00016     # cost data
00017     cost = dict(zip(managed_topics, (dynamic_bandwidth_manager.DBMParam.get_message_size_in_bytes(topic) for topic in managed_topics)))
00018 
00019     # Create the objective
00020     #model += sum(cost[i] * f[i] for i in managed_topics)
00021     for topic in managed_topics:
00022         model += f[topic]
00023 
00024     available_bandwidth_in_mbits = dynamic_bandwidth_manager.DBMParam.get_max_bandwidth_in_mbits() * dynamic_bandwidth_manager.DBMParam.get_max_bandwidth_utilization()
00025     available_bandwidth_in_bytes = available_bandwidth_in_mbits * 1310720
00026 
00027     # Constraints:
00028     # The total bandwidth should be lower than max bandwidth available
00029     model += sum(cost[i] * f[i] for i in managed_topics) <= available_bandwidth_in_bytes
00030 
00031     # The frequency should be higher than minimum frequency
00032     # Calculating the minimum frequency in relation to the priority
00033     fmin = dict(zip(managed_topics,
00034                 (((dynamic_bandwidth_manager.DBMParam.get_max_frequency(topic) - dynamic_bandwidth_manager.DBMParam.get_min_frequency(topic)) * dynamic_bandwidth_manager.DBMParam.get_priority(topic) + dynamic_bandwidth_manager.DBMParam.get_min_frequency(topic))
00035                 for topic in managed_topics)))
00036 
00037     for topic in managed_topics:
00038             model += f[topic] >= fmin[topic]
00039 
00040     # The frequency should be lower than maximum frequency
00041     fmax = dict(zip(managed_topics,
00042         (dynamic_bandwidth_manager.DBMParam.get_max_frequency(topic) for topic in managed_topics)))
00043     for topic in managed_topics:
00044         model += f[topic] <= fmax[topic]
00045 
00046     # Problem is then solved with the default solver
00047     model.solve()
00048 
00049     # Create the result dictionary
00050     result = {}
00051     if model.status == 1:
00052         for topic in managed_topics:
00053             result[topic] = f[topic].value()
00054 
00055     print 'Available bandwidth: (%s mbits / %s bytes)' %(available_bandwidth_in_mbits, available_bandwidth_in_bytes)
00056     print 'fmin: %s' %(fmin)
00057     print 'fmax: %s' %(fmax)
00058     if model.status == 1: print 'Result: %s' %(result)
00059     else: print 'Result: %s' %(result)
00060 
00061     return result
00062         
00063 if __name__ == '__main__':
00064     try:
00065         rospy.init_node('default_optimizer', anonymous=True)
00066         optimizer = dynamic_bandwidth_manager.DBMOptimizer(optimize)
00067         optimizer.start()
00068 
00069     except rospy.ROSInterruptException: pass


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