def __init__(self, title, parent = None): super().__init__(Qt.Horizontal, parent) self.param = UserData.getInstance().getUserDataEntry(UD_PLOTTER_WINDOW_KEY, {}) self.setWindowTitle(title) self.plotMessages = { 'RAW_IMU' : None, 'SCALED_IMU' : None, 'GPS_RAW_INT' : None, 'ATTITUDE' : None, 'SCALED_PRESSURE' : None } self.chart = PlotterPanel() self.chartView = QChartView(self.chart) self.chartView.setRenderHint(QPainter.Antialiasing) self.plotControl = PlotItemMenu() self.plotControl.plotDataSignal.connect(self.chart.toggleDataVisibility) spLeft = QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred) spLeft.setHorizontalStretch(1) self.plotControl.setSizePolicy(spLeft) spRight = QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred) spRight.setHorizontalStretch(6) self.chartView.setSizePolicy(spRight) self.addWidget(self.plotControl) self.addWidget(self.chartView) if UD_PLOTTER_WINDOW_HEIGHT_KEY in self.param and UD_PLOTTER_WINDOW_WIDTH_KEY in self.param: self.resize(self.param[UD_PLOTTER_WINDOW_WIDTH_KEY], self.param[UD_PLOTTER_WINDOW_HEIGHT_KEY])
def __init__(self, connection, replayMode=False, enableLog=True): super().__init__() self.internalHandlerLookup = {} self.mavStatus = {MavStsKeys.AP_SYS_ID: 1} self.isConnected = False # self.paramList = [] self.paramPanel = None self.txLock = QMutex() # uplink lock self.txResponseCond = QWaitCondition() self.txTimeoutTimer = QTimer() self.finalWPSent = False self.wpLoader = MAVWPLoader() self.onboardWPCount = 0 self.numberOfonboardWP = 0 self.onboardWP = [] self.mavlinkLogFile = None self.lastMessageReceivedTimestamp = 0.0 self.lastMessages = {} # type = (msg, timestamp) self.param = UserData.getInstance().getUserDataEntry( UD_TELEMETRY_KEY, {}) self.messageTimeoutThreshold = UserData.getParameterValue( self.param, UD_TELEMETRY_TIMEOUT_THRESHOLD_KEY, MAVLinkConnection.DEFAULT_MESSAGE_TIMEOUT_THRESHOLD) self.txTimeoutmsec = self.messageTimeoutThreshold * 1000000 # timeout for wait initial heartbeat signal self.initHeartbeatTimeout = UserData.getParameterValue( self.param, UD_TELEMETRY_HEARTBEAT_TIMEOUT_KEY, MAVLinkConnection.DEFAULT_HEARTBEAT_TIMEOUT) self.txMessageQueue = deque() self.running = True self.connection = connection self.replayMode = replayMode self.enableLog = enableLog self.uas = None if replayMode: self.enableLog = False connection.replayCompleteSignal.connect(self.requestExit) self.internalHandlerLookup[ 'PARAM_VALUE'] = self.receiveOnboardParameter self.internalHandlerLookup[ 'MISSION_REQUEST'] = self.receiveMissionRequest self.internalHandlerLookup[ 'MISSION_ACK'] = self.receiveMissionAcknowledge self.internalHandlerLookup[ 'MISSION_COUNT'] = self.receiveMissionItemCount self.internalHandlerLookup['MISSION_ITEM'] = self.receiveMissionItem self.internalHandlerLookup['DATA_STREAM'] = self.receiveDataStream self.internalHandlerLookup['PARAM_SET'] = self.receiveParameterSet self.txTimeoutTimer.timeout.connect(self._timerTimeout) self.txTimeoutTimer.setSingleShot(True)
def __init__(self, parent=None): super().__init__(parent) self.mav = None self.param = UserData.getInstance().getUserDataEntry( UD_MAIN_WINDOW_KEY, {}) current_path = os.path.abspath(os.path.dirname(__file__)) qmlFile = os.path.join(current_path, './instruments/map.qml') self.setWindowTitle('Mini GCS') if UD_MAIN_WINDOW_HEIGHT_KEY in self.param and UD_MAIN_WINDOW_WIDTH_KEY in self.param: self.resize(self.param[UD_MAIN_WINDOW_WIDTH_KEY], self.param[UD_MAIN_WINDOW_HEIGHT_KEY]) self.teleWindow = ConnectionEditWindow() self.teleWindow.MAVLinkConnectedSignal.connect(self.createConnection) self.window = QSplitter() self.left = QSplitter(Qt.Vertical, self.window) self.pfd = PrimaryFlightDisplay(self.window) self.sts = SystemStatusPanel(self.window) self.msgSignWindow = MessageSigningSetupWindow() self.hudWindow = HUDWindow() self.hud = self.hudWindow.hud self.sts.connectToMAVLink.connect(self.teleWindow.show) self.sts.disconnectFromMAVLink.connect(self.disconnect) spPfd = QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred) spPfd.setVerticalStretch(3) self.pfd.setSizePolicy(spPfd) spSts = QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred) spSts.setVerticalStretch(2) self.sts.setSizePolicy(spSts) self.left.addWidget(self.pfd) self.left.addWidget(self.sts) spLeft = QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred) spLeft.setHorizontalStretch(2) self.left.setSizePolicy(spLeft) self.map = MapWidget(qmlFile) spRight = QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred) spRight.setHorizontalStretch(5) self.map.setSizePolicy(spRight) self.window.addWidget(self.left) self.window.addWidget(self.map) self.localGPSWindow = GPSConfigurationWindow() # TODO configurable behavior self.localGPSWindow.connection.locationUpdate.connect( self.map.updateHomeLocationEvent) self.sts.connectToLocalGPS.connect(self.localGPSWindow.show) self.sts.disconnectFromLocalGPS.connect( self.localGPSWindow.connection.disconnect) self.sts.statusPanel.showHUDButton.clicked.connect(self.hudWindow.show) self.teleWindow.cancelConnectionSignal.connect( lambda: self.sts.statusPanel.connectButton.setEnabled(True)) self.__createMenus() self.setCentralWidget(self.window)
def closeEvent(self, event): print('[MAIN] closeEvent') ud = UserData.getInstance() s = self.size() self.param[UD_MAIN_WINDOW_HEIGHT_KEY] = s.height() self.param[UD_MAIN_WINDOW_WIDTH_KEY] = s.width() ud.setUserDataEntry(UD_MAIN_WINDOW_KEY, self.param) try: ud.saveGCSConfiguration() print('GCS Conf saved.') except IOError: pass super().closeEvent(event)
def __init__(self, parent): super().__init__(parent) self.instrumentOpagueBackground = QBrush( QColor.fromHsvF(0, 0, 0.3, 1.0)) self.instrumentBackground = QBrush(QColor.fromHsvF(0, 0, 0.3, 0.3)) self.instrumentEdgePen = QPen(QColor.fromHsvF(0, 0, 0.65, 0.5)) self.font = QFont() self.lineWidth = 2 self.fineLineWidth = 1 self.navigationTargetBearing = PrimaryFlightDisplay.UNKNOWN_ATTITUDE self.navigationCrosstrackError = 0 self.primaryAltitude = PrimaryFlightDisplay.UNKNOWN_ALTITUDE self.GPSAltitude = PrimaryFlightDisplay.UNKNOWN_ALTITUDE self.verticalVelocity = PrimaryFlightDisplay.UNKNOWN_ALTITUDE self.primarySpeed = PrimaryFlightDisplay.UNKNOWN_SPEED self.groundspeed = PrimaryFlightDisplay.UNKNOWN_SPEED self.roll = 0.0 self.pitch = 0.0 self.yaw = 0.0 self.rollspeed = 0.0 self.pitchspeed = 0.0 self.yawspeed = 0.0 self.latitude = 0.0 self.longitude = 0.0 self.additionalParameters = {} self.param = UserData.getInstance().getUserDataEntry(UD_PFD_KEY, {}) self.isGPSSpeedPrimary = UserData.getParameterValue( self.param, UD_PFD_PRIMARY_SPEED_SOURCE_KEY) == 'GPS' self.isGPSAltitudePrimary = UserData.getParameterValue( self.param, UD_PFD_PRIMARY_ALTITUDE_SOURCE_KEY) == 'GPS' self.setMinimumSize(480, 320) self.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) self.smallTestSize = self.SMALL_TEXT_SIZE self.mediumTextSize = self.MEDIUM_TEXT_SIZE self.largeTextSize = self.LARGE_TEXT_SIZE self.uiTimer = QTimer(self) self.uiTimer.setInterval(40) self.uiTimer.timeout.connect(self.update) self.uas = None
def __init__(self, name, parent=None): super().__init__(parent) self.uasName = name self.autopilotClass = mavlink.MAV_AUTOPILOT_GENERIC self.param = UserData.getInstance().getUserDataEntry( UD_UAS_CONF_KEY, {}) self.onboardParameters = [] self.oldOnboardParameters = [] self.onboardParamNotReceived = 0 self.messageHandlers = {} self.messageHandlers['SYS_STATUS'] = self.uasStatusHandler self.messageHandlers['GPS_RAW_INT'] = self.uasLocationHandler self.messageHandlers[ 'GLOBAL_POSITION_INT'] = self.uasFilteredLocationHandler self.messageHandlers['SCALED_PRESSURE'] = self.uasAltitudeHandler self.messageHandlers['ATTITUDE'] = self.uasAttitudeHandler self.messageHandlers['GPS_STATUS'] = self.uasGPSStatusHandler self.messageHandlers['RADIO_STATUS'] = self.uasRadioStatusHandler self.messageHandlers['RC_CHANNELS'] = self.uasRCChannelsHandler self.messageHandlers[ 'NAV_CONTROLLER_OUTPUT'] = self.uasNavigationControllerOutputHandler self.messageHandlers[ 'LOCAL_POSITION_NED'] = self.uasDefaultMessageHandler self.messageHandlers['PARAM_VALUE'] = self.uasDefaultMessageHandler self.messageHandlers['HEARTBEAT'] = self.uasDefaultMessageHandler self.messageHandlers[ 'ATTITUDE_QUATERNION'] = self.uasDefaultMessageHandler self.messageHandlers['SYSTEM_TIME'] = self.uasDefaultMessageHandler self.messageHandlers['VFR_HUD'] = self.uasDefaultMessageHandler self.messageHandlers[ 'AUTOPILOT_VERSION'] = self.uasDefaultMessageHandler self.messageHandlers['BATTERY_STATUS'] = self.uasDefaultMessageHandler self.messageHandlers['SCALED_IMU'] = self.uasDefaultMessageHandler self.messageHandlers['RAW_IMU'] = self.uasDefaultMessageHandler self.altitudeReference = DEFAULT_ALTITUDE_REFERENCE self.pressureReference = DEFAULT_PRESSURE_REFERENCE self.signingKey = None self.initialTimestamp = 0
self.mav.connection.WIRE_PROTOCOL_VERSION) self.mav.start() def disconnect(self): self.mav.requestExit() def closeEvent(self, event): print('[MAIN] closeEvent') ud = UserData.getInstance() s = self.size() self.param[UD_MAIN_WINDOW_HEIGHT_KEY] = s.height() self.param[UD_MAIN_WINDOW_WIDTH_KEY] = s.width() ud.setUserDataEntry(UD_MAIN_WINDOW_KEY, self.param) try: ud.saveGCSConfiguration() print('GCS Conf saved.') except IOError: pass super().closeEvent(event) if __name__ == '__main__': app = QApplication(sys.argv) try: UserData.getInstance().loadGCSConfiguration() except IOError: sys.exit(1) frame = MiniGCS() frame.show() sys.exit(app.exec_())
def __getLastConnectionParameter(self): pParam = UserData.getInstance().getUserDataEntry(UD_TELEMETRY_KEY, {}) return UserData.getParameterValue(pParam, UD_TELEMETRY_LAST_CONNECTION_KEY, {})