Only released in EOL distros:
Package Summary
dynamic_bandwidth_manager is a ros-based dynamic bandwidth management system for controlling the rate that a node publishes a topic, managing different channels where commands, sensory data and video frames are exchanged
- Maintainer: Ricardo Emerson Julio <ricardo AT gmail DOT com>
- Author: Ricardo Emerson Julio <ricardo AT gmail DOT com>, Guilherme Sousa Bastos <sousa AT unifei.edu DOT br>
- License: BSD
- Source: git https://github.com/ricardoej/dynamic_bandwidth_manager.git (branch: master)
Contents
Overview
Communication is an important component in multi-robots systems; system performance may get affected when the number of robots or communication channels increases. The dynamic_bandwidth_manager was designed to provide a way of maximizing bandwidth usage in multi-robots systems. The developed system prioritizes communication channels according to environment events and offers greater bandwidth for the most important channels.
The package architecture was divided in five libraries and one ROS node. DBMParam is a library to help developers manipulate the parameters of the module. DBMRate is a library that extends the function of the rospy.Rate and helps to run loops at a dynamic frequency. Classes DBMSubscriber and DBMPublisher inherits the characteristics of rospy.Subscriber and rospy.Publisher. DBMOptimizer class helps developers create new optimization strategies. Node default_optimizer uses the class DBMOptimizer and solves a linear optimization problem calculating new frequencies for each topic, considering topic priority and message size.
Paper
A paper named Dynamic Bandwidth Management Library for Multi-Robot Systems will be presented at IROS 2015.
System Parameters
Basic Usage
Writing a Simple Publisher using dynamic_bandwidth_manager package
1 #!/usr/bin/env python
2 # license removed for brevity
3 import rospy
4 import dynamic_bandwidth_manager
5 from rescue_app.msg import RescueInfo
6
7 # Returns the message to be published
8 def getMessage():
9 return hello_str = "hello world %s" % rospy.get_time()
10
11 def run():
12 # Minimum frequency of 10hz and maximum frequency of 24hz
13 pub = dynamic_bandwidth_manager.DBMPublisher(
14 'chatter', RescueInfo, 10, 24)
15 rospy.init_node('talker', anonymous=True)
16
17 # Starts message publish with the frequency stored in the Parameter Server
18 pub.start(getMessage)
19
20 if __name__ == '__main__':
21 try:
22 run()
23 except rospy.ROSInterruptException:
24 pass
Running optimization node
To create the independence of the optimization algorithm used by the library, a module that takes care of the bandwidth optimization was created. DBMOptimizer is a ROS library that helps the development of more complex strategies for the optimization problem. It runs every time as /dbm/optimization_rate parameter and assigns the result of the calculated frequencies in parameter [topic_name]/dbm/frequency/current_value. Using DBMOptimizer, default_optimizer node solves a linear optimization problem and sets the calculated frequency for each topic considering the priorities (see [topic_name]/dbm/priority parameter).
Writing new optimization strategies
Using DBMOptimizer it's possible create new optimization strategies. Code below presents a example of how create a node with a optimization algorithm.
1 #!/usr/bin/env python
2
3 import rospy
4 import dynamic_bandwidth_manager
5 import pulp
6 import numpy as np
7
8 def optimize(managed_topics):
9 # Makes the optimization and returns a dictionary of type
10 # [topic_name:frequency_value] (the managed_topics parameter has a list of topics
11 # that must be taken into consideration in the optimization)
12
13 if __name__ == '__main__':
14 try:
15 rospy.init_node('default_optimizer', anonymous=True)
16 optimizer = dynamic_bandwidth_manager.DBMOptimizer(optimize)
17 optimizer.start()
18
19 except rospy.ROSInterruptException: pass
Managing topics on same machine
If one of these topics has its rate controlled by the library, it is treated as a managed channel. But the question is how to manage channels that just send messages to other nodes that are running in the same machine? In these cases, the topic has no impact in the bandwidth and should be ignored when optimization is running. Thus, the DBMOptimizer decides which topics should be managed in a specific time verifying if there are external nodes communicating with the topic. If there is no external node subscribing to the topic, it is not treated as a managed channel and has its frequency adjusted to its maximum value.
Another important question is when the topic has subscribers in nodes running in external machines and in the same machine of the topic. If the system limits the global sampling and publishing rate for that topic, this would mean that a local process, not subject to the same bandwidth limitations, would not get the full rate data from the topic. To solve this problem, the system creates two topics for each managed topic: a full rate topic ([topic_name]) and a managed rate topic ([topic_name]/managed). Thus, when a client of the topic is running in the same machine of the managed topic, it subscribes in the full rate topic. However, if the client is running in an external machine, it is subscribed in the managed rate topic. So, the full rate topic stream would still be available for local processing/logging.