|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +""" |
| 4 | + MAVProxy instructor station, UI runs in a child process |
| 5 | + André Kjellstrup @ NORCE |
| 6 | +""" |
| 7 | + |
| 8 | +from MAVProxy.modules.lib import mp_util |
| 9 | +from MAVProxy.modules.lib import multiproc |
| 10 | +from MAVProxy.modules.lib.wx_loader import wx |
| 11 | + |
| 12 | + |
| 13 | +class CheckboxItemState: |
| 14 | + def __init__(self, name, state): |
| 15 | + self.name = name |
| 16 | + self.state = state |
| 17 | + |
| 18 | + |
| 19 | +class InstructorUI: |
| 20 | + """ |
| 21 | + Instructor UI for MAVProxy |
| 22 | + """ |
| 23 | + def __init__(self, title='Instructor Station'): |
| 24 | + self.title = title |
| 25 | + self.menu_callback = None |
| 26 | + self.pipe_to_gui, self.gui_pipe = multiproc.Pipe() |
| 27 | + self.close_event = multiproc.Event() |
| 28 | + self.close_event.clear() |
| 29 | + self.child = multiproc.Process(target=self.child_task) |
| 30 | + self.child.start() |
| 31 | + |
| 32 | + def child_task(self): |
| 33 | + """child process - this holds all the GUI elements""" |
| 34 | + mp_util.child_close_fds() |
| 35 | + from MAVProxy.modules.lib.wx_loader import wx |
| 36 | + |
| 37 | + app = wx.App(False) |
| 38 | + app.frame = InstructorFrame(self.gui_pipe, state=self, title=self.title) |
| 39 | + app.frame.Show() |
| 40 | + app.MainLoop() |
| 41 | + |
| 42 | + def close(self): |
| 43 | + """close the UI""" |
| 44 | + self.close_event.set() |
| 45 | + if self.is_alive(): |
| 46 | + self.child.join(2) |
| 47 | + print("closed") |
| 48 | + |
| 49 | + def is_alive(self): |
| 50 | + """check if child is still going""" |
| 51 | + return self.child.is_alive() |
| 52 | + |
| 53 | + def set_check(self, name, state): |
| 54 | + """set a status value""" |
| 55 | + if self.child.is_alive(): |
| 56 | + self.pipe_to_gui.send(CheckboxItemState(name, state)) |
| 57 | + |
| 58 | + |
| 59 | +class InstructorFrame(wx.Frame): |
| 60 | + """ The main frame of the console""" |
| 61 | + |
| 62 | + def __init__(self, gui_pipe, state, title): |
| 63 | + self.state = state |
| 64 | + self.gui_pipe = gui_pipe |
| 65 | + wx.Frame.__init__(self, None, title=title, size=(500, 650), style=wx.DEFAULT_FRAME_STYLE ^ wx.RESIZE_BORDER) |
| 66 | + |
| 67 | + |
| 68 | + self.panel = wx.Panel(self) |
| 69 | + self.nb = wx.Choicebook(self.panel, wx.ID_ANY) |
| 70 | + |
| 71 | + # create the tabs |
| 72 | + self.createWidgets() |
| 73 | + |
| 74 | + # assign events to the buttons on the tabs |
| 75 | + self.createActions() |
| 76 | + |
| 77 | + # add in the pipe from MAVProxy |
| 78 | + self.timer = wx.Timer(self) |
| 79 | + # self.Bind(wx.EVT_TIMER, self.on_timer, self.timer) |
| 80 | + # self.Bind(wx.EVT_TIMER, self.on_timer, self.timer) |
| 81 | + self.Bind(wx.EVT_TIMER, lambda evt, notebook=self.nb: self.on_timer(evt, notebook), self.timer) |
| 82 | + self.timer.Start(100) |
| 83 | + |
| 84 | + # finally, put the notebook in a sizer for the panel to manage |
| 85 | + # the layout |
| 86 | + sizer = wx.BoxSizer() |
| 87 | + sizer.Add(self.nb, 1, wx.EXPAND) |
| 88 | + self.panel.SetSizer(sizer) |
| 89 | + |
| 90 | + self.Show(True) |
| 91 | + self.pending = [] |
| 92 | + |
| 93 | + |
| 94 | + |
| 95 | + # create controls on form - labels, buttons, etc |
| 96 | + def createWidgets(self): |
| 97 | + |
| 98 | + # create the panels for the tabs |
| 99 | + |
| 100 | + PanelCommon = wx.Panel(self.nb) |
| 101 | + boxCommon = wx.BoxSizer(wx.VERTICAL) |
| 102 | + PanelCommon.SetAutoLayout(True) |
| 103 | + PanelCommon.SetSizer(boxCommon) |
| 104 | + PanelCommon.Layout() |
| 105 | + |
| 106 | + |
| 107 | + PanelPlane = wx.Panel(self.nb) |
| 108 | + boxPlane = wx.BoxSizer(wx.VERTICAL) |
| 109 | + PanelPlane.SetAutoLayout(True) |
| 110 | + PanelPlane.SetSizer(boxPlane) |
| 111 | + PanelPlane.Layout() |
| 112 | + |
| 113 | + PanelCopter = wx.Panel(self.nb) |
| 114 | + boxCopter = wx.BoxSizer(wx.VERTICAL) |
| 115 | + PanelCopter.SetAutoLayout(True) |
| 116 | + PanelCopter.SetSizer(boxCopter) |
| 117 | + PanelCopter.Layout() |
| 118 | + |
| 119 | + |
| 120 | + # add the data to the individual tabs |
| 121 | + |
| 122 | + 'Common failures' |
| 123 | + |
| 124 | + self.Dis_GNSS_Fix_Checkbox = wx.CheckBox(PanelCommon, wx.ID_ANY, "Disable GNSS FIX") |
| 125 | + boxCommon.Add(self.Dis_GNSS_Fix_Checkbox) |
| 126 | + |
| 127 | + boxCommon.Add(wx.StaticLine(PanelCommon, -1), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 10) |
| 128 | + boxCommon.Add(wx.StaticText(PanelCommon, wx.ID_ANY, 'Voltage drop rate mv/s:', wx.DefaultPosition, wx.DefaultSize, style=wx.ALIGN_RIGHT)) |
| 129 | + |
| 130 | + self.VoltageSlider = wx.Slider(PanelCommon, wx.ID_ANY, 100, 10, 200, wx.DefaultPosition, (250, -1), |
| 131 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 132 | + boxCommon.Add(self.VoltageSlider) |
| 133 | + |
| 134 | + self.Voltage_Drop_Checkbox = wx.CheckBox(PanelCommon, wx.ID_ANY, "Voltage dropping") |
| 135 | + boxCommon.Add(self.Voltage_Drop_Checkbox) |
| 136 | + |
| 137 | + boxCommon.Add(wx.StaticLine(PanelCommon, -1), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 10) |
| 138 | + |
| 139 | + self.FailsafeButton = wx.Button(PanelCommon, wx.ID_ANY, "Trigger FailSafe") |
| 140 | + boxCommon.Add(self.FailsafeButton) |
| 141 | + |
| 142 | + boxCommon.Add(wx.StaticLine(PanelCommon, -1), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 10) |
| 143 | + |
| 144 | + self.GCS_Comm_Loss_Checkbox = wx.CheckBox(PanelCommon, wx.ID_ANY, "GCS Comm loss") |
| 145 | + # disCheckbox.Enable(False) |
| 146 | + boxCommon.Add(self.GCS_Comm_Loss_Checkbox) |
| 147 | + |
| 148 | + boxCommon.Add(wx.StaticLine(PanelCommon, -1), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 10) |
| 149 | + boxCommon.Add(wx.StaticText(PanelCommon, wx.ID_ANY, 'Wind Direction:', wx.DefaultPosition, wx.DefaultSize,style=wx.ALIGN_RIGHT)) |
| 150 | + |
| 151 | + self.Wind_Dir_Slider = wx.Slider(PanelCommon, wx.ID_ANY, 0, 0, 359, wx.DefaultPosition, (250, -1), |
| 152 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 153 | + boxCommon.Add(self.Wind_Dir_Slider) |
| 154 | + |
| 155 | + boxCommon.Add(wx.StaticText(PanelCommon, wx.ID_ANY, 'Wind Velocity (m/s):', wx.DefaultPosition, wx.DefaultSize,style=wx.ALIGN_RIGHT)) |
| 156 | + self.Wind_Vel_Slider = wx.Slider(PanelCommon, wx.ID_ANY, 0, 0, 50, wx.DefaultPosition, (250, -1), |
| 157 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 158 | + boxCommon.Add(self.Wind_Vel_Slider) |
| 159 | + |
| 160 | + boxCommon.Add(wx.StaticText(PanelCommon, wx.ID_ANY, 'Turbulence:', wx.DefaultPosition, wx.DefaultSize, |
| 161 | + style=wx.ALIGN_RIGHT)) |
| 162 | + self.Wind_Turb_Slider = wx.Slider(PanelCommon, wx.ID_ANY, 0, 0, 10, wx.DefaultPosition, (250, -1), |
| 163 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 164 | + boxCommon.Add(self.Wind_Turb_Slider) |
| 165 | + |
| 166 | + |
| 167 | + 'Plane specific failures' |
| 168 | + |
| 169 | + self.Pitot_Fail_Low_Checkbox = wx.CheckBox(PanelPlane, wx.ID_ANY, "Pitot stuck at no speed") |
| 170 | + boxPlane.Add(self.Pitot_Fail_Low_Checkbox) |
| 171 | + |
| 172 | + self.Pitot_Fail_High_Checkbox = wx.CheckBox(PanelPlane, wx.ID_ANY, "Pitot stuck at high speed") |
| 173 | + boxPlane.Add(self.Pitot_Fail_High_Checkbox) |
| 174 | + |
| 175 | + self.Arspd_Offset_Slider = wx.Slider(PanelPlane, wx.ID_ANY, 2013, 1500, 2500, wx.DefaultPosition, (250, -1), |
| 176 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 177 | + boxPlane.Add(self.Arspd_Offset_Slider) |
| 178 | + |
| 179 | + boxPlane.Add(wx.StaticLine(PanelPlane, -1), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 10) |
| 180 | + |
| 181 | + boxPlane.Add(wx.StaticText(PanelPlane, wx.ID_ANY, 'Thrust reduction:', wx.DefaultPosition, wx.DefaultSize, |
| 182 | + style=wx.ALIGN_RIGHT)) |
| 183 | + self.Plane_Thrust_Slider = wx.Slider(PanelPlane, wx.ID_ANY, 0, 0, 1000, wx.DefaultPosition, (250, -1), |
| 184 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 185 | + boxPlane.Add(self.Plane_Thrust_Slider) |
| 186 | + |
| 187 | + boxPlane.Add(wx.StaticText(PanelPlane, wx.ID_ANY, 'Thrust reduction + current increase:', wx.DefaultPosition, wx.DefaultSize, |
| 188 | + style=wx.ALIGN_RIGHT)) |
| 189 | + |
| 190 | + self.Plane_Thrust_Curr_Slider = wx.Slider(PanelPlane, wx.ID_ANY, 0, 0, 1000, wx.DefaultPosition, (250, -1), |
| 191 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 192 | + boxPlane.Add(self.Plane_Thrust_Curr_Slider) |
| 193 | + |
| 194 | + 'Copter specific failures' |
| 195 | + |
| 196 | + boxCopter.Add(wx.StaticText(PanelCopter, wx.ID_ANY, 'Thrust reduction:', wx.DefaultPosition, wx.DefaultSize, style=wx.ALIGN_RIGHT)) |
| 197 | + |
| 198 | + self.Copter_Thrust_Slider = wx.Slider(PanelCopter, wx.ID_ANY, 0, 0, 400, wx.DefaultPosition, (250, -1), |
| 199 | + wx.SL_AUTOTICKS | wx.SL_HORIZONTAL | wx.SL_LABELS) |
| 200 | + boxCopter.Add(self.Copter_Thrust_Slider) |
| 201 | + |
| 202 | + boxCopter.Add(wx.StaticLine(PanelCopter, -1), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 10) |
| 203 | + |
| 204 | + self.CopterResetButton = wx.Button(PanelCopter, wx.ID_ANY, "Reset Parameters") |
| 205 | + boxCopter.Add(self.CopterResetButton) |
| 206 | + |
| 207 | + # and add in the tabs |
| 208 | + self.nb.AddPage(PanelCommon, "Common (Copter/Plane) Failures") |
| 209 | + self.nb.AddPage(PanelPlane, "Plane specific Failures") |
| 210 | + self.nb.AddPage(PanelCopter, "Copter specific Failures") |
| 211 | + |
| 212 | + |
| 213 | + |
| 214 | + |
| 215 | + # Create the actions for the buttons |
| 216 | + def createActions(self): |
| 217 | + # Common tab: |
| 218 | + self.Bind(wx.EVT_CHECKBOX, self.dis_gnss, self.Dis_GNSS_Fix_Checkbox) |
| 219 | + #self.Bind(wx.EVT_CHECKBOX, self.sendevent("Voltage", 20), self.Voltage_Drop_Checkbox) # WHY trigged once? |
| 220 | + self.Bind(wx.EVT_CHECKBOX, self.volt_drop, self.Voltage_Drop_Checkbox) |
| 221 | + self.Bind(wx.EVT_CHECKBOX, self.gcs_comm_loss, self.GCS_Comm_Loss_Checkbox) |
| 222 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.volt_drop_rate, self.VoltageSlider) |
| 223 | + self.Bind(wx.EVT_BUTTON, self.setmode, self.FailsafeButton) |
| 224 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.wind_dir, self.Wind_Dir_Slider) |
| 225 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.wind_vel, self.Wind_Vel_Slider) |
| 226 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.wind_turbulence, self.Wind_Turb_Slider) |
| 227 | + # Plane tab: |
| 228 | + self.Bind(wx.EVT_CHECKBOX, self.pitot_fail_low, self.Pitot_Fail_Low_Checkbox) |
| 229 | + self.Bind(wx.EVT_CHECKBOX, self.pitot_fail_high, self.Pitot_Fail_High_Checkbox) |
| 230 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.arspd_offset, self.Arspd_Offset_Slider) |
| 231 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.plane_thrust_loss, self.Plane_Thrust_Slider) |
| 232 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.plane_thrust_loss_curr, self.Plane_Thrust_Curr_Slider) |
| 233 | + # Copter tab: |
| 234 | + self.Bind(wx.EVT_SCROLL_CHANGED, self.copter_thrust_loss, self.Copter_Thrust_Slider) |
| 235 | + self.Bind(wx.EVT_BUTTON, self.copter_reset, self.CopterResetButton) |
| 236 | + |
| 237 | + # Common actions |
| 238 | + def dis_gnss(self, event): |
| 239 | + self.gui_pipe.send(["dis_gnss", self.Dis_GNSS_Fix_Checkbox.Value]) |
| 240 | + |
| 241 | + def volt_drop_rate(self, event): |
| 242 | + self.gui_pipe.send(["volt_drop_rate", self.VoltageSlider.Value / 1000]) |
| 243 | + |
| 244 | + def volt_drop(self, event): |
| 245 | + self.gui_pipe.send(["volt_drop", self.Voltage_Drop_Checkbox.Value]) |
| 246 | + |
| 247 | + def gcs_comm_loss(self, event): |
| 248 | + self.gui_pipe.send(["gcs_comm_loss", self.GCS_Comm_Loss_Checkbox.Value]) |
| 249 | + |
| 250 | + def setmode(self, event): |
| 251 | + self.gui_pipe.send(["setmode", 10]) |
| 252 | + def on_gnss_Button_ok(self, event): |
| 253 | + self.gui_pipe.send("ok") |
| 254 | + |
| 255 | + def wind_dir(self, event): |
| 256 | + self.gui_pipe.send(["wind_dir", self.Wind_Dir_Slider.Value]) |
| 257 | + |
| 258 | + def wind_vel(self, event): |
| 259 | + self.gui_pipe.send(["wind_vel", self.Wind_Vel_Slider.Value]) |
| 260 | + |
| 261 | + |
| 262 | + def wind_turbulence(self, event): |
| 263 | + self.gui_pipe.send(["wind_turbulence", self.Wind_Turb_Slider.Value]) |
| 264 | + |
| 265 | + # Plane actions |
| 266 | + |
| 267 | + def pitot_fail_low(self, event): |
| 268 | + self.gui_pipe.send(["pitot_fail_low", self.Pitot_Fail_Low_Checkbox.Value]) |
| 269 | + |
| 270 | + def pitot_fail_high(self, event): |
| 271 | + self.gui_pipe.send(["pitot_fail_high", self.Pitot_Fail_High_Checkbox.Value]) |
| 272 | + |
| 273 | + def arspd_offset(self, event): |
| 274 | + self.gui_pipe.send(["arspd_offset", self.Arspd_Offset_Slider.Value]) |
| 275 | + |
| 276 | + def plane_thrust_loss(self, event): |
| 277 | + self.gui_pipe.send(["plane_thrust_loss", self.Plane_Thrust_Slider.Value]) |
| 278 | + |
| 279 | + def plane_thrust_loss_curr(self, event): |
| 280 | + self.gui_pipe.send(["plane_thrust_loss_curr", self.Plane_Thrust_Curr_Slider.Value]) |
| 281 | + |
| 282 | + # Copter actions |
| 283 | + |
| 284 | + def copter_thrust_loss(self, event): |
| 285 | + self.gui_pipe.send(["copter_thrust_loss", self.Copter_Thrust_Slider.Value]) |
| 286 | + |
| 287 | + def copter_reset (self, event): |
| 288 | + self.gui_pipe.send(["copter_reset", 0]) |
| 289 | + |
| 290 | + def sendevent(self, event, text, value=0): |
| 291 | + self.gui_pipe.send([text, value]) |
| 292 | + |
| 293 | + |
| 294 | + |
| 295 | + |
| 296 | + #do a final check of the current panel and move to the next |
| 297 | + def on_Button( self, event): |
| 298 | + win = (event.GetEventObject()).GetParent() |
| 299 | + for widget in win.GetChildren(): |
| 300 | + if type(widget) is wx.CheckBox and widget.IsChecked() == 0: |
| 301 | + dlg = wx.MessageDialog(win, "Not all items checked", "Error", wx.OK | wx.ICON_WARNING) |
| 302 | + dlg.ShowModal() |
| 303 | + dlg.Destroy() |
| 304 | + return |
| 305 | + # all checked, go to next panel. |
| 306 | + win.GetParent().AdvanceSelection() |
| 307 | + |
| 308 | + |
| 309 | + # Receive messages from MAVProxy module and process them |
| 310 | + def on_timer(self, event, notebook): |
| 311 | + state = self.state |
| 312 | + win = notebook.GetPage(notebook.GetSelection()) |
| 313 | + if state.close_event.wait(0.001): |
| 314 | + self.timer.Stop() |
| 315 | + self.Destroy() |
| 316 | + return |
| 317 | + while state.gui_pipe.poll(): |
| 318 | + obj = state.gui_pipe.recv() |
| 319 | + if isinstance(obj, CheckboxItemState): |
| 320 | + # go through each item in the current tab and (un)check as needed |
| 321 | + # print(obj.name + ", " + str(obj.state)) |
| 322 | + for widget in win.GetChildren(): |
| 323 | + if type(widget) is wx.CheckBox and widget.GetLabel() == obj.name: |
| 324 | + widget.SetValue(obj.state) |
| 325 | + |
| 326 | + |
| 327 | +if __name__ == "__main__": |
| 328 | + # test the console |
| 329 | + import time |
| 330 | + |
| 331 | + instructor = InstructorUI() |
| 332 | + |
| 333 | + # example auto-tick in second tab page |
| 334 | + while instructor.is_alive(): |
| 335 | + time.sleep(0.5) |
0 commit comments