mavtelemetry_datarates.py 8.8 KB

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