Go to the documentation of this file.00001
00002
00003 import Gnuplot
00004 import time
00005 import numpy
00006 import rospy
00007 from std_msgs.msg import Float32
00008
00009 gp=Gnuplot.Gnuplot()
00010
00011 plot_topic = rospy.get_param("~plot_topic", [('/eth0/receive', 'reveive'), ('eth0/transmit', 'transmit')])
00012
00013 max_y = rospy.get_param("~max_y", 1200000)
00014 data_scale = rospy.get_param("~data_scale", 0.001)
00015
00016 data_rate = rospy.get_param("~data_rate", 100)
00017 period = rospy.get_param("~period", 120)
00018 drop_num = rospy.get_param("~drop_num", 10)
00019 drop_index = [0 for i in range(len(plot_topic))]
00020
00021 xrange = (period, 0)
00022 yrange = (0, (int)(max_y * data_scale))
00023
00024 xlabel = rospy.get_param("~x_label", "Time (s)")
00025 ylabel = rospy.get_param("~y_label", "Network Data Rates (kbps)")
00026 title = rospy.get_param("~title", "Network Status")
00027
00028 plot_size = data_rate * period / drop_num
00029
00030 y_list = [numpy.zeros(plot_size) for i in range(len(plot_topic))]
00031 x = numpy.arange(plot_size) / float(plot_size / period)
00032
00033 def callback(msg, index):
00034 global drop_index
00035 if drop_index[index] != drop_num:
00036 drop_index[index] = drop_index[index] + 1
00037 return
00038 drop_index[index] = 0
00039
00040 global y_list
00041
00042 y_list[index] = numpy.delete(y_list[index], plot_size - 1)
00043 y_list[index] = numpy.insert(y_list[index], 0, msg.data * data_scale)
00044 try:
00045 d_list = [Gnuplot.Data(x, y, title=plot_topic[i][1], with_='lines linewidth 2') for (i, y) in enumerate(y_list)]
00046 if len(d_list) == 1:
00047 gp.plot(d_list[0])
00048 elif len(d_list) == 2:
00049 gp.plot(d_list[0], d_list[1])
00050 elif len(y_list) == 3:
00051 gp.plot(d_list[0], d_list[1])
00052 elif len(y_list) == 4:
00053 gp.plot(d_list[0], d_list[1])
00054 elif len(y_list) == 5:
00055 gp.plot(d_list[0], d_list[1])
00056 elif len(y_list) == 6:
00057 gp.plot(d_list[0], d_list[1])
00058 except:
00059 pass
00060
00061 if __name__ == '__main__':
00062 rospy.init_node("network_plot")
00063 for i in range(len(plot_topic)):
00064 topic = plot_topic[i][0]
00065 rospy.Subscriber(topic, Float32, callback, callback_args = i)
00066
00067 gp.set(xrange=xrange, yrange=yrange, title=title, xlabel=xlabel, ylabel=ylabel)
00068 rospy.spin()