mavtelemetry_datarates.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 GUI to calculate telemetry data rate between vehicle and GCS
4 
5 Amilcar Lucas
6 Karthik Desai
7 
8 Copyright IAV GmbH 2017
9 Released under GNU GPL version 3 or later
10 '''
11 
12 from future import standard_library
13 standard_library.install_aliases()
14 from builtins import str
15 
16 ## Generate window for calculating the datasize
17 from tkinter import Tk, Text, TOP, BOTH, X, Y, N, LEFT,RIGHT, CENTER, RIDGE, VERTICAL, END, IntVar, IntVar, Scrollbar
18 from tkinter.ttk import Frame, Label, Entry, Combobox, Checkbutton
19 
20 # import MAVLink messages length dictionary
21 # this file is generated by a script
22 mavlink_message_lengths_dict = None # default if following lines fail
23 mav_message_size = 'mavlink_messages_size.py'
24 exec(compile(source=open(mav_message_size).read(), filename=mav_message_size, mode='exec'))
25 
26 # Please adapt this list to the vehicle you are using
27 # These were done by looking at the GCS_MAVLINK_Copter::data_stream_send() function
28 # in the ardupilot/ArduCopter/GCS_Mavlink.cpp file
29 mavlink_streams_list = [
30 # STREAM DEFAULT DEFAULT DEFAULT
31 # NAME RATE MAVLINK CHECKBOX
32 # [Hz] MESSAGE STATES
33  ("RAW_SENS", 0, [('RAW_IMU' , True),
34  ('SCALED_IMU2' , True),
35  ('SCALED_IMU3' , False),
36  ('SCALED_PRESSURE' , True),
37  ('SCALED_PRESSURE2' , True),
38  ('SCALED_PRESSURE3' , False),
39  ('SENSOR_OFFSETS' , True),
40  ('NONE' , False)]),
41  ("EXT_STAT", 1, [('SYS_STATUS' , True),
42  ('POWER_STATUS' , True),
43  ('MEMINFO' , True),
44  ('MISSION_CURRENT' , True),
45  ('GPS_RAW_INT' , True),
46  ('GPS_RTK' , False),
47  ('GPS2_RAW' , False),
48  ('GPS2_RTK' , False),
49  ('NAV_CONTROLLER_OUTPUT', True),
50  ('FENCE_STATUS' , False),
51  ('NONE' , False)]),
52  ("POSITION", 1, [('GLOBAL_POSITION_INT' , True),
53  ('LOCAL_POSITION_NED' , True),
54  ('NONE' , False)]),
55  ("RAW_CTRL", 0, [('RC_CHANNELS_SCALED' , True),
56  ('NONE' , False)]),
57  ("RC_CHAN", 0, [('SERVO_OUTPUT_RAW' , True),
58  ('RC_CHANNELS_RAW' , True),
59  ('RC_CHANNELS' , True),
60  ('NONE' , False)]),
61  ("EXTRA1", 2, [('ATTITUDE' , True),
62  ('SIMSTATE' , False),
63  ('AHRS2' , True),
64  ('PID_TUNING' , False), # TODO: this will be sent up to four times depending on the GCS_PID_MASK bit3~0 parameter
65  ('NONE' , False)]),
66  ("EXTRA2", 2, [('VFR_HUD' , True),
67  ('NONE' , False)]),
68  ("EXTRA3", 1, [('AHRS' , True),
69  ('HWSTATUS' , True),
70  ('SYSTEM_TIME' , True),
71  ('RANGEFINDER' , False),
72  ('DISTANCE_SENSOR' , False),
73  ('TERRAIN_REQUEST' , False),
74  ('BATTERY2' , False),
75  ('MOUNT_STATUS' , False),
76  ('OPTICAL_FLOW' , False),
77  ('GIMBAL_REPORT' , False),
78  ('MAG_CAL_REPORT' , False),
79  ('MAG_CAL_PROGRESS' , False),
80  ('EKF_STATUS_REPORT' , True),
81  ('VIBRATION' , True),
82  ('RPM' , True),
83  ('NONE' , False)]),
84 # ("PARAMS", 8, [('PARAM_VALUE' , True),
85 # ('NONE' ,False)]),
86  ("ADSB", 0, [('ADSB_VEHICLE' , True),
87  ('NONE' , False)]),
88  ("RTCM_INJ", 1, [('GPS_RTCM_DATA' , True),
89  ('NONE' , False)]),
90 ]
91 
92 
93 class MainWindow(Frame):
94  def __init__(self, parent):
95 
96  Frame.__init__(self, parent)
97  self.parent = parent
102  # you can change this one to make the GUI wider
103  self.columns = 3
104  self.initUI()
105 
106  self.parent.bind('<Return>', self.updateCombo)
107  self.updateCombo()
108 
109  def updateCombo(self, event = None):
110  totalBits = 0
111  for frame_name in mavlink_streams_list:
112  bits = 0
113  for frame_boxes in frame_name[2]:
114  temp = self.streamrate_name_array[frame_name[0]][frame_boxes[0]].get()
115  if (self.streamrate_cb_array[frame_name[0]][frame_boxes[0]].get()):
116  bits = bits + (8*mavlink_message_lengths_dict[temp]) # convert number of bytes to number of bits
117  datarate = float(self.streamrate_edit_array[frame_name[0]].get())
118  tempDataBits = int(bits * datarate)
119  self.streamDataRate_array[frame_name[0]].config(text=str(tempDataBits)+" bits/s")
120  totalBits = int(totalBits + tempDataBits)
121  self.end_total_data_rate_label.config(text = "Total Data Rate is "+str(totalBits) + " bits/s")
122 
123 
124  def initUI(self):
125 
126  self.parent.title("Calculate Mavlink UAV->GCS telemetry datarate")
127  self.pack(fill=BOTH, expand=1)
128 
129  count = 0
130  count_frame = 0
131  count_row = 0
132  for frame_name in mavlink_streams_list:
133  child_frame = Frame(self,borderwidth = 2, relief = RIDGE)
134  child_frame.grid(row = count_row, column = count_frame % self.columns)
135  if(count_frame % self.columns == self.columns-1):
136  count_row = count_row + 1
137  count_frame = count_frame + 1
138 
139  frame_label = Label(child_frame, text = frame_name[0] + " message stream")
140  frame_label.pack(side= TOP)
141 
142  self.streamrate_name_array[frame_name[0]] = {}
143  self.streamrate_cb_array[frame_name[0]] = {}
144 
145  comboFrame = Frame(child_frame)
146  comboFrame.pack(side = LEFT)
147  for frame_boxes in frame_name[2] :
148 
149  comboframe = Frame(comboFrame)
150  comboframe.pack(side = TOP)
151 
152  combo = Combobox(comboframe,values = tuple(mavlink_msg_temp for mavlink_msg_temp in mavlink_message_lengths_dict))
153  combo.grid(row = count, column = 0)
154  index = list(mavlink_message_lengths_dict.keys()).index(frame_boxes[0])
155  combo.current(index)
156 
157  var = IntVar()
158  if (frame_boxes[1]):
159  var.set(1)
160  else:
161  var.set(0)
162  checkbox = Checkbutton(comboframe,variable = var, command = self.updateCombo)
163  checkbox.grid(row = count, column = 1)
164 
165  self.streamrate_name_array[frame_name[0]][frame_boxes[0]] = combo
166  self.streamrate_cb_array[frame_name[0]][frame_boxes[0]] = var
167 
168  combo.bind("<<ComboboxSelected>>",self.updateCombo)
169  count = count + 1
170 
171  streamrate_frame = Frame(child_frame)
172  streamrate_frame.pack(side = TOP, anchor = CENTER)
173  data_rate_label = Label(streamrate_frame, text="Stream Rate")
174  data_rate_label.pack()
175 
176  self.data_rate_edit = Entry(streamrate_frame,width = 2)
177  self.data_rate_edit.insert(0,frame_name[1])
178  self.streamrate_edit_array[frame_name[0]] = self.data_rate_edit
179  self.data_rate_edit.pack(side = LEFT, anchor = CENTER)
180 
181  unit_Label = Label(streamrate_frame, text="Hz")
182  unit_Label.pack(side=RIGHT,anchor = CENTER)
183 
184  datarate_frame = Frame(child_frame)
185  datarate_frame.pack(side = TOP, anchor = CENTER)
186  total_data_rate_label = Label(datarate_frame, text="Data Rate")
187  total_data_rate_label.pack(side=TOP,anchor = CENTER)
188  self.total_data_rate_answer = Label(datarate_frame, text=" bits/s")
189  self.total_data_rate_answer.pack(side=TOP,anchor = CENTER)
190  self.streamDataRate_array[frame_name[0]] = self.total_data_rate_answer
191 
192  self.end_total_data_rate_label = Label(self.parent, text="Total Data Rate")
193  self.end_total_data_rate_label.pack(side=TOP)
194 
195 
196 def main():
197  root = Tk()
198  app = MainWindow(root)
199  root.mainloop()
200 
201 
202 if __name__ == '__main__':
203  main()


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02