3 GUI to calculate telemetry data rate between vehicle and GCS 8 Copyright IAV GmbH 2017 9 Released under GNU GPL version 3 or later 12 from future
import standard_library
13 standard_library.install_aliases()
14 from builtins
import str
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
22 mavlink_message_lengths_dict =
None 23 mav_message_size =
'mavlink_messages_size.py' 24 exec(compile(source=open(mav_message_size).read(), filename=mav_message_size, mode=
'exec'))
29 mavlink_streams_list = [
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),
41 (
"EXT_STAT", 1, [(
'SYS_STATUS' ,
True),
42 (
'POWER_STATUS' ,
True),
44 (
'MISSION_CURRENT' ,
True),
45 (
'GPS_RAW_INT' ,
True),
49 (
'NAV_CONTROLLER_OUTPUT',
True),
50 (
'FENCE_STATUS' ,
False),
52 (
"POSITION", 1, [(
'GLOBAL_POSITION_INT' ,
True),
53 (
'LOCAL_POSITION_NED' ,
True),
55 (
"RAW_CTRL", 0, [(
'RC_CHANNELS_SCALED' ,
True),
57 (
"RC_CHAN", 0, [(
'SERVO_OUTPUT_RAW' ,
True),
58 (
'RC_CHANNELS_RAW' ,
True),
59 (
'RC_CHANNELS' ,
True),
61 (
"EXTRA1", 2, [(
'ATTITUDE' ,
True),
64 (
'PID_TUNING' ,
False),
66 (
"EXTRA2", 2, [(
'VFR_HUD' ,
True),
68 (
"EXTRA3", 1, [(
'AHRS' ,
True),
70 (
'SYSTEM_TIME' ,
True),
71 (
'RANGEFINDER' ,
False),
72 (
'DISTANCE_SENSOR' ,
False),
73 (
'TERRAIN_REQUEST' ,
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),
86 (
"ADSB", 0, [(
'ADSB_VEHICLE' ,
True),
88 (
"RTCM_INJ", 1, [(
'GPS_RTCM_DATA' ,
True),
96 Frame.__init__(self, parent)
111 for frame_name
in mavlink_streams_list:
113 for frame_boxes
in frame_name[2]:
116 bits = bits + (8*mavlink_message_lengths_dict[temp])
118 tempDataBits =
int(bits * datarate)
120 totalBits =
int(totalBits + tempDataBits)
121 self.end_total_data_rate_label.config(text =
"Total Data Rate is "+
str(totalBits) +
" bits/s")
126 self.parent.title(
"Calculate Mavlink UAV->GCS telemetry datarate")
127 self.pack(fill=BOTH, expand=1)
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)
136 count_row = count_row + 1
137 count_frame = count_frame + 1
139 frame_label = Label(child_frame, text = frame_name[0] +
" message stream")
140 frame_label.pack(side= TOP)
145 comboFrame = Frame(child_frame)
146 comboFrame.pack(side = LEFT)
147 for frame_boxes
in frame_name[2] :
149 comboframe = Frame(comboFrame)
150 comboframe.pack(side = TOP)
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])
162 checkbox = Checkbutton(comboframe,variable = var, command = self.
updateCombo)
163 checkbox.grid(row = count, column = 1)
168 combo.bind(
"<<ComboboxSelected>>",self.
updateCombo)
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()
177 self.data_rate_edit.insert(0,frame_name[1])
179 self.data_rate_edit.pack(side = LEFT, anchor = CENTER)
181 unit_Label = Label(streamrate_frame, text=
"Hz")
182 unit_Label.pack(side=RIGHT,anchor = CENTER)
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)
189 self.total_data_rate_answer.pack(side=TOP,anchor = CENTER)
193 self.end_total_data_rate_label.pack(side=TOP)
202 if __name__ ==
'__main__':
def __init__(self, parent)
def updateCombo(self, event=None)
end_total_data_rate_label