diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index 13756cb9a044b6860c5558b3dee467468ad0511f..606ca5947fb9744c36d766c70c693bbb12cc7dd8 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -5,57 +5,6 @@ WindowsBuild { INCLUDEPATH += libs/lib/msinttypes } -# -# [OPTIONAL] QUpgrade support. -# -# Allow the user to override QUpgrade compilation through a DISABLE_QUPGRADE -# define like: `qmake DEFINES=DISABLE_QUPGRADE` -contains(DEFINES, DISABLE_QUPGRADE) { - message("Skipping support for QUpgrade (manual override from command line)") - DEFINES -= DISABLE_QUPGRADE -} -# Otherwise the user can still disable this feature in the user_config.pri file. -else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_QUPGRADE) { - message("Skipping support for QUpgrade (manual override from user_config.pri)") -} -# If the QUpgrade submodule has been initialized, build in support by default. -# We look for the existence of qupgrade.pro for the check. We can't look for a .git file -# because that breaks the TeamCity build process which does not use repositories. -else:exists(qupgrade/qupgrade.pro) { - message("Including support for QUpgrade") - - DEFINES += QGC_QUPGRADE_ENABLED - - INCLUDEPATH += qupgrade/src/apps/qupgrade - - FORMS += \ - qupgrade/src/apps/qupgrade/dialog_bare.ui \ - qupgrade/src/apps/qupgrade/boardwidget.ui - - HEADERS += \ - qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.h \ - qupgrade/src/apps/qupgrade/uploader.h \ - qupgrade/src/apps/qupgrade/dialog_bare.h \ - qupgrade/src/apps/qupgrade/boardwidget.h - - SOURCES += \ - qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.cpp \ - qupgrade/src/apps/qupgrade/uploader.cpp \ - qupgrade/src/apps/qupgrade/dialog_bare.cpp \ - qupgrade/src/apps/qupgrade/boardwidget.cpp - - RESOURCES += \ - qupgrade/qupgrade.qrc - - LinuxBuild:CONFIG += qesp_linux_udev - - include(qupgrade/libs/qextserialport/src/qextserialport.pri) -} -# Otherwise notify the user and don't compile it. -else { - warning("Skipping support for QUpgrade (missing submodule, see README)") -} - # # [REQUIRED] Add support for the MAVLink communications protocol. # Some logic is involved here in selecting the proper dialect for diff --git a/QGCSetup.pri b/QGCSetup.pri index 861859f17bd6c8243c0935491bca89ea6398ba90..9ca615beac0d80fcb8642e62019265286a532ac7 100644 --- a/QGCSetup.pri +++ b/QGCSetup.pri @@ -39,12 +39,10 @@ WindowsBuild { DESTDIR_COPY_RESOURCE_LIST = $$replace(DESTDIR,"/","\\") BASEDIR_COPY_RESOURCE_LIST = $$replace(BASEDIR,"/","\\") QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$BASEDIR_COPY_RESOURCE_LIST\\files\" \"$$DESTDIR_COPY_RESOURCE_LIST\\files\" - QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$BASEDIR_COPY_RESOURCE_LIST\\qml\" \"$$DESTDIR_COPY_RESOURCE_LIST\\qml\" QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$BASEDIR_COPY_RESOURCE_LIST\\data\" \"$$DESTDIR_COPY_RESOURCE_LIST\\data\" } else { # Make sure to keep both side of this if using the same set of directories QMAKE_POST_LINK += && $$QMAKE_COPY_DIR $$BASEDIR/files $$DESTDIR_COPY_RESOURCE_LIST - QMAKE_POST_LINK += && $$QMAKE_COPY_DIR $$BASEDIR/qml $$DESTDIR_COPY_RESOURCE_LIST QMAKE_POST_LINK += && $$QMAKE_COPY_DIR $$BASEDIR/data $$DESTDIR_COPY_RESOURCE_LIST } diff --git a/files/images/px4/boards/px4flow_1.x.png b/files/images/px4/boards/px4flow_1.x.png new file mode 100644 index 0000000000000000000000000000000000000000..0f396aa7c8e47cacc0191a91563b74e1ad220728 Binary files /dev/null and b/files/images/px4/boards/px4flow_1.x.png differ diff --git a/files/images/px4/boards/px4fmu_1.x.png b/files/images/px4/boards/px4fmu_1.x.png new file mode 100644 index 0000000000000000000000000000000000000000..294fa975ba9aa5086e849ad720e428df90136ed3 Binary files /dev/null and b/files/images/px4/boards/px4fmu_1.x.png differ diff --git a/files/images/px4/boards/px4fmu_2.x.png b/files/images/px4/boards/px4fmu_2.x.png new file mode 100644 index 0000000000000000000000000000000000000000..0a26a6883e64f5438de9d22b6c6bb322818eb81f Binary files /dev/null and b/files/images/px4/boards/px4fmu_2.x.png differ diff --git a/libs/opmapcontrol/src/core/urlfactory.cpp b/libs/opmapcontrol/src/core/urlfactory.cpp index 9a3f52dcec68dfce87d1be9e068fbcb9df19d25c..9b3bb6fa9c19d8230b173452eaba00a3029315a7 100644 --- a/libs/opmapcontrol/src/core/urlfactory.cpp +++ b/libs/opmapcontrol/src/core/urlfactory.cpp @@ -210,7 +210,8 @@ namespace core { QString sec2 = ""; // after &zoom=... GetSecGoogleWords(pos, sec1, sec2); TryCorrectGoogleVersions(); - return QString("https://%1%2.google.com/%3/v=%4&hl=%5&x=%6%7&y=%8&z=%9&s=%10").arg(server).arg(GetServerNum(pos, 4)).arg(request).arg(VersionGoogleSatellite).arg(language).arg(pos.X()).arg(sec1).arg(pos.Y()).arg(zoom).arg(sec2); + //this does not yield good results in practice return QString("https://%1%2.google.com/%3/v=%4&hl=%5&x=%6%7&y=%8&z=%9&s=%10").arg(server).arg(GetServerNum(pos, 4)).arg(request).arg(VersionGoogleSatellite).arg(language).arg(pos.X()).arg(sec1).arg(pos.Y()).arg(zoom).arg(sec2); + return QString("http://mt1.google.com/vt/lyrs=y&x=%1%2&y=%3&z=%4").arg(pos.X()).arg(sec1).arg(pos.Y()).arg(zoom); } break; case MapType::GoogleLabels: diff --git a/libs/opmapcontrol/src/internals/tilematrix.cpp b/libs/opmapcontrol/src/internals/tilematrix.cpp index cedfd7fba50a2f91fd229866058b6848311edc36..ce96a1a7d19fca86d331f1a3f7df3eabc8bb4d23 100644 --- a/libs/opmapcontrol/src/internals/tilematrix.cpp +++ b/libs/opmapcontrol/src/internals/tilematrix.cpp @@ -100,7 +100,7 @@ void TileMatrix::Clear() void TileMatrix::ClearPointsNotIn(QListlist) { removals.clear(); - mutex.lock(); + QMutexLocker lock(&mutex); foreach(Point p, matrix.keys()) { if(!list.contains(p)) @@ -108,17 +108,14 @@ void TileMatrix::ClearPointsNotIn(QListlist) removals.append(p); } } - mutex.unlock(); foreach(Point p,removals) { - Tile* t=TileAt(p); + Tile* t=matrix.value(p, 0); if(t!=0) { - mutex.lock(); delete t; t=0; matrix.remove(p); - mutex.unlock(); } } diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 0b5b58c437968fc4c751e145090c4b80777cab09..9977780b048eda02d058dc7d49ff26053e2f0a26 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -45,6 +45,7 @@ linux { macx-clang | macx-llvm { message("Mac build") CONFIG += MacBuild + QMAKE_MAC_SDK = macosx10.9 } else { error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported") } @@ -136,6 +137,7 @@ MacBuild { LinuxBuild { DEFINES += __STDC_LIMIT_MACROS + CONFIG += qesp_linux_udev } WindowsBuild { @@ -244,6 +246,7 @@ INCLUDEPATH += \ src/ui/mission \ src/ui/designer \ src/ui/configuration \ + src/ui/px4_configuration \ src/ui/main FORMS += \ @@ -321,42 +324,16 @@ FORMS += \ src/ui/uas/QGCMessageView.ui \ src/ui/JoystickButton.ui \ src/ui/JoystickAxis.ui \ - src/ui/configuration/ApmHardwareConfig.ui \ - src/ui/configuration/ApmSoftwareConfig.ui \ - src/ui/configuration/FrameTypeConfig.ui \ - src/ui/configuration/CompassConfig.ui \ - src/ui/configuration/AccelCalibrationConfig.ui \ - src/ui/configuration/RadioCalibrationConfig.ui \ - src/ui/configuration/FlightModeConfig.ui \ - src/ui/configuration/Radio3DRConfig.ui \ - src/ui/configuration/BatteryMonitorConfig.ui \ - src/ui/configuration/SonarConfig.ui \ - src/ui/configuration/AirspeedConfig.ui \ - src/ui/configuration/OpticalFlowConfig.ui \ - src/ui/configuration/OsdConfig.ui \ - src/ui/configuration/AntennaTrackerConfig.ui \ - src/ui/configuration/CameraGimbalConfig.ui \ - src/ui/configuration/BasicPidConfig.ui \ - src/ui/configuration/StandardParamConfig.ui \ - src/ui/configuration/GeoFenceConfig.ui \ - src/ui/configuration/FailSafeConfig.ui \ - src/ui/configuration/AdvancedParamConfig.ui \ - src/ui/configuration/ArduCopterPidConfig.ui \ - src/ui/configuration/ApmPlaneLevel.ui \ - src/ui/configuration/ParamWidget.ui \ - src/ui/configuration/ArduPlanePidConfig.ui \ - src/ui/configuration/AdvParameterList.ui \ - src/ui/configuration/ArduRoverPidConfig.ui \ src/ui/QGCConfigView.ui \ src/ui/main/QGCViewModeSelection.ui \ src/ui/main/QGCWelcomeMainWindow.ui \ src/ui/configuration/terminalconsole.ui \ src/ui/configuration/SerialSettingsDialog.ui \ - src/ui/configuration/ApmFirmwareConfig.ui \ src/ui/px4_configuration/QGCPX4AirframeConfig.ui \ src/ui/px4_configuration/QGCPX4MulticopterConfig.ui \ src/ui/px4_configuration/QGCPX4SensorCalibration.ui \ src/ui/px4_configuration/PX4RCCalibration.ui \ + src/ui/px4_configuration/PX4FirmwareUpgrade.ui \ src/ui/QGCUASFileView.ui HEADERS += \ @@ -407,7 +384,6 @@ HEADERS += \ src/ui/QGCSensorSettingsWidget.h \ src/ui/linechart/Linecharts.h \ src/uas/PxQuadMAV.h \ - src/uas/ArduPilotMegaMAV.h \ src/uas/senseSoarMAV.h \ src/ui/watchdog/WatchdogControl.h \ src/ui/watchdog/WatchdogProcessView.h \ @@ -499,34 +475,6 @@ HEADERS += \ src/ui/uas/QGCMessageView.h \ src/ui/JoystickButton.h \ src/ui/JoystickAxis.h \ - src/ui/configuration/ApmHardwareConfig.h \ - src/ui/configuration/ApmSoftwareConfig.h \ - src/ui/configuration/FrameTypeConfig.h \ - src/ui/configuration/CompassConfig.h \ - src/ui/configuration/AccelCalibrationConfig.h \ - src/ui/configuration/RadioCalibrationConfig.h \ - src/ui/configuration/FlightModeConfig.h \ - src/ui/configuration/Radio3DRConfig.h \ - src/ui/configuration/BatteryMonitorConfig.h \ - src/ui/configuration/SonarConfig.h \ - src/ui/configuration/AirspeedConfig.h \ - src/ui/configuration/OpticalFlowConfig.h \ - src/ui/configuration/OsdConfig.h \ - src/ui/configuration/AntennaTrackerConfig.h \ - src/ui/configuration/CameraGimbalConfig.h \ - src/ui/configuration/AP2ConfigWidget.h \ - src/ui/configuration/BasicPidConfig.h \ - src/ui/configuration/StandardParamConfig.h \ - src/ui/configuration/GeoFenceConfig.h \ - src/ui/configuration/FailSafeConfig.h \ - src/ui/configuration/AdvancedParamConfig.h \ - src/ui/configuration/ArduCopterPidConfig.h \ - src/ui/apmtoolbar.h \ - src/ui/configuration/ApmPlaneLevel.h \ - src/ui/configuration/ParamWidget.h \ - src/ui/configuration/ArduPlanePidConfig.h \ - src/ui/configuration/AdvParameterList.h \ - src/ui/configuration/ArduRoverPidConfig.h \ src/ui/QGCConfigView.h \ src/ui/main/QGCViewModeSelection.h \ src/ui/main/QGCWelcomeMainWindow.h \ @@ -534,7 +482,6 @@ HEADERS += \ src/ui/configuration/SerialSettingsDialog.h \ src/ui/configuration/terminalconsole.h \ src/ui/configuration/ApmHighlighter.h \ - src/ui/configuration/ApmFirmwareConfig.h \ src/uas/UASParameterDataModel.h \ src/uas/UASParameterCommsMgr.h \ src/ui/QGCPendingParamWidget.h \ @@ -543,6 +490,9 @@ HEADERS += \ src/ui/px4_configuration/QGCPX4MulticopterConfig.h \ src/ui/px4_configuration/QGCPX4SensorCalibration.h \ src/ui/px4_configuration/PX4RCCalibration.h \ + src/ui/px4_configuration/PX4Bootloader.h \ + src/ui/px4_configuration/PX4FirmwareUpgradeThread.h \ + src/ui/px4_configuration/PX4FirmwareUpgrade.h \ src/ui/menuactionhelper.h \ src/uas/UASManagerInterface.h \ src/uas/QGCUASParamManagerInterface.h \ @@ -595,7 +545,6 @@ SOURCES += \ src/ui/QGCSensorSettingsWidget.cc \ src/ui/linechart/Linecharts.cc \ src/uas/PxQuadMAV.cc \ - src/uas/ArduPilotMegaMAV.cc \ src/uas/senseSoarMAV.cpp \ src/ui/watchdog/WatchdogControl.cc \ src/ui/watchdog/WatchdogProcessView.cc \ @@ -684,34 +633,6 @@ SOURCES += \ src/ui/JoystickButton.cc \ src/ui/JoystickAxis.cc \ src/ui/uas/QGCMessageView.cc \ - src/ui/configuration/ApmHardwareConfig.cc \ - src/ui/configuration/ApmSoftwareConfig.cc \ - src/ui/configuration/FrameTypeConfig.cc \ - src/ui/configuration/CompassConfig.cc \ - src/ui/configuration/AccelCalibrationConfig.cc \ - src/ui/configuration/RadioCalibrationConfig.cc \ - src/ui/configuration/FlightModeConfig.cc \ - src/ui/configuration/Radio3DRConfig.cc \ - src/ui/configuration/BatteryMonitorConfig.cc \ - src/ui/configuration/SonarConfig.cc \ - src/ui/configuration/AirspeedConfig.cc \ - src/ui/configuration/OpticalFlowConfig.cc \ - src/ui/configuration/OsdConfig.cc \ - src/ui/configuration/AntennaTrackerConfig.cc \ - src/ui/configuration/CameraGimbalConfig.cc \ - src/ui/configuration/AP2ConfigWidget.cc \ - src/ui/configuration/BasicPidConfig.cc \ - src/ui/configuration/StandardParamConfig.cc \ - src/ui/configuration/GeoFenceConfig.cc \ - src/ui/configuration/FailSafeConfig.cc \ - src/ui/configuration/AdvancedParamConfig.cc \ - src/ui/configuration/ArduCopterPidConfig.cc \ - src/ui/apmtoolbar.cpp \ - src/ui/configuration/ApmPlaneLevel.cc \ - src/ui/configuration/ParamWidget.cc \ - src/ui/configuration/ArduPlanePidConfig.cc \ - src/ui/configuration/AdvParameterList.cc \ - src/ui/configuration/ArduRoverPidConfig.cc \ src/ui/QGCConfigView.cc \ src/ui/main/QGCViewModeSelection.cc \ src/ui/main/QGCWelcomeMainWindow.cc \ @@ -719,7 +640,6 @@ SOURCES += \ src/ui/configuration/console.cpp \ src/ui/configuration/SerialSettingsDialog.cc \ src/ui/configuration/ApmHighlighter.cc \ - src/ui/configuration/ApmFirmwareConfig.cc \ src/uas/UASParameterDataModel.cc \ src/uas/UASParameterCommsMgr.cc \ src/ui/QGCPendingParamWidget.cc \ @@ -728,6 +648,9 @@ SOURCES += \ src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \ src/ui/px4_configuration/QGCPX4SensorCalibration.cc \ src/ui/px4_configuration/PX4RCCalibration.cc \ + src/ui/px4_configuration/PX4Bootloader.cc \ + src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc \ + src/ui/px4_configuration/PX4FirmwareUpgrade.cc \ src/ui/menuactionhelper.cpp \ src/uas/QGCUASFileManager.cc \ src/ui/QGCUASFileView.cc \ @@ -758,7 +681,6 @@ HEADERS += \ src/qgcunittest/MockMavlinkInterface.h \ src/qgcunittest/MockMavlinkFileServer.h \ src/qgcunittest/MultiSignalSpy.h \ - src/qgcunittest/FlightModeConfigTest.h \ src/qgcunittest/FlightGearTest.h \ src/qgcunittest/TCPLinkTest.h \ src/qgcunittest/TCPLoopBackServer.h \ @@ -772,7 +694,6 @@ SOURCES += \ src/qgcunittest/MockQGCUASParamManager.cc \ src/qgcunittest/MockMavlinkFileServer.cc \ src/qgcunittest/MultiSignalSpy.cc \ - src/qgcunittest/FlightModeConfigTest.cc \ src/qgcunittest/FlightGearTest.cc \ src/qgcunittest/TCPLinkTest.cc \ src/qgcunittest/TCPLoopBackServer.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 31686a27f7b0b60b4b3289b6b152e889d9faf058..5a7d9cdaece71becfacb7e7e073d8eabee05eec4 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -199,6 +199,9 @@ files/images/px4/calibration/3dr_gps/gps_24.png files/images/px4/calibration/3dr_gps/gps_00.png files/images/px4/menu/toggle_switch.png + files/images/px4/boards/px4flow_1.x.png + files/images/px4/boards/px4fmu_1.x.png + files/images/px4/boards/px4fmu_2.x.png files/styles/Vera.ttf diff --git a/qml/ApmToolBar.qml b/qml/ApmToolBar.qml deleted file mode 100644 index 6ede1e51d419c6e1a9a554889a20a91837a2e826..0000000000000000000000000000000000000000 --- a/qml/ApmToolBar.qml +++ /dev/null @@ -1,210 +0,0 @@ -import QtQuick 2.1 -import "./components" - - -Rectangle { - id: toolbar - - property alias backgroundColor : toolbar.color - property alias linkNameLabel: linkDevice.label - property alias baudrateLabel: baudrate.label - property bool connected: false - property bool armed: false - property string armedstr: "DISARMED" - - width: toolbar.width - height: 72 - color: "black" - border.color: "black" - - onArmedChanged: { - if (armed) { - statusDisplay.statusText = "ARMED" - statusDisplay.statusTextColor = "red" - statusDisplay.statusBackgroundColor = "#FF880000" - } - else { - statusDisplay.statusText = "DISARMED" - statusDisplay.statusTextColor = "yellow" - statusDisplay.statusBackgroundColor = "black" - } - } - - onConnectedChanged: { - if (connected){ - console.log("APM Tool BAR QML: connected") - connectButton.image = "./resources/qgroundcontrol/toolbar/disconnect.png" - connectButton.label = "DISCONNECT" - } else { - console.log("APM Tool BAR QML: disconnected") - connectButton.image = "./resources/qgroundcontrol/toolbar/connect.png" - connectButton.label = "CONNECT" - } - } - -// [BB] The code below should work, not sure why. replaced with code above -// Connections { -// target: globalObj -// onMAVConnected: { -// console.log("QML Change Connection " + connected) -// if (connected){ -// console.log("connected") -// connectButton.image = "./resources/qgroundcontrol/toolbar/disconnect.png" -// } else { -// console.log("disconnected") -// connectButton.image = "./resources/qgroundcontrol/toolbar/connect.png" -// } -// } -// } - - Row { - anchors.left: parent.left - spacing: 10 - - Rectangle { // Spacer - width: 5 - height: parent.height - color: "black" - } - - Button { - id: flightDataView - label: "FLIGHT DATA" - image: "./resources/qgroundcontrol/toolbar/flightdata.png" - onClicked: { - globalObj.triggerFlightView() - } - } - - Button { - id: flightPlanView - label: "FLIGHT PLAN" - image: "./resources/qgroundcontrol/toolbar/flightplanner.png" - onClicked: globalObj.triggerFlightPlanView() - } - - Button { - id: hardwareConfigView - label: "HARDWARE" - image: "./resources/qgroundcontrol/toolbar/hardwareconfig.png" - margins: 8 - onClicked: globalObj.triggerHardwareView() - } - - Button { - id: softwareConfigView - label: "SOFTWARE" - image: "./resources/qgroundcontrol/toolbar/softwareconfig.png" - margins: 8 - onClicked: globalObj.triggerSoftwareView() - } - - Button { - id: simulationView - label: "SIMULATION" - image: "./resources/qgroundcontrol/toolbar/simulation.png" - onClicked: globalObj.triggerSimulationView() - } - - Button { - id: terminalView - label: "TERMINAL" - image: "./resources/qgroundcontrol/toolbar/terminal.png" - onClicked: globalObj.triggerTerminalView() - } - - Rectangle { // Spacer - width: 5 - height: parent.height - color: "black" - } - - StatusDisplay { - id: statusDisplay - width: 110 - statusText: "DISARMED" - statusTextColor: "yellow" - statusBackgroundColor: "black" - } - - Rectangle { // Spacer - width: 5 - height: parent.height - color: "black" - } - -// [BB] Commented out ToolBar Status info work. -// WIP: To be fixed later -// DigitalDisplay { // Information Pane -// title:"Mode" -// textValue: "Stabilize" -// color: "black" -// } -// DigitalDisplay { // Information Pane -// title: "Speed" -// textValue: "11.0m/s" -// color: "black" -// } -// DigitalDisplay { // Information Pane -// title: "Alt" -// textValue: "20.0m" -// color: "black" -// } -// DigitalDisplay { // Information Pane -// title: "Volts" -// textValue: "14.8V" -// color: "black" -// } -// DigitalDisplay { // Information Pane -// title: "Current" -// textValue: "12.0A" -// color: "black" -// } -// DigitalDisplay { // Information Pane -// title: "Level" -// textValue: "77%" -// color: "black" -// } - - } - - Row { - anchors.right: parent.right - spacing: 2 - - TextButton { - id: linkDevice - label: "none" - minWidth: 100 - - onClicked: globalObj.showConnectionDialog() - } - - TextButton { - id: baudrate - label: "none" - minWidth: 100 - - onClicked: globalObj.showConnectionDialog() - } - - Rectangle { - width: 5 - height: parent.height - color: "black" - } - - Button { - id: connectButton - label: "CONNECT" - image: "./resources/qgroundcontrol/toolbar/connect.png" - onClicked: globalObj.connectMAV() - } - - Rectangle { // Spacer - width: 5 - height: parent.height - color: "black" - } - } -} diff --git a/qml/components/Button.qml b/qml/components/Button.qml deleted file mode 100644 index 27b1f9e337c7842362bcb64bf44d7ecb61306fd0..0000000000000000000000000000000000000000 --- a/qml/components/Button.qml +++ /dev/null @@ -1,70 +0,0 @@ -import QtQuick 2.1 - -Rectangle { - signal clicked - - property string label: "button label" - property alias image: buttonImage.source - property int margins: 2 - - id: button - width: 72 - height: 72 - radius: 3 - smooth: true - border.width: 2 - - Text { - id: buttonLabel - anchors.top: parent.top - anchors.horizontalCenter: parent.horizontalCenter - anchors.margins: 5 - text: label - color: "white" - font.pointSize: 10 - } - - Image { - id: buttonImage - anchors.horizontalCenter: button.horizontalCenter - anchors.top: buttonLabel.bottom - anchors.margins: margins - source: image - fillMode: Image.PreserveAspectFit - width: image.width - height: image.height - } - - signal buttonClick() - - onButtonClick: { - console.log(buttonLabel.text + " clicked calling signal") - clicked() - } - - // Highlighting and ativation section - property color buttonColor: "black" - property color onHoverbuttonColor: "lightblue" - property color onHoverColor: "darkblue" - property color borderColor: "black" - - MouseArea { - id: buttonMouseArea - anchors.fill: parent - onClicked: buttonClick() - hoverEnabled: true - onEntered: { - parent.border.color = onHoverColor - parent.color = onHoverbuttonColor - } - onExited: { - parent.border.color = borderColor - parent.color = buttonColor - } - onPressed: parent.color = Qt.darker(onHoverbuttonColor, 1.5) - onReleased: parent.color = buttonColor - } - color: buttonColor - border.color: borderColor -} - diff --git a/qml/components/DigitalDisplay.qml b/qml/components/DigitalDisplay.qml deleted file mode 100644 index 5af486b5a4179118d35dd49703f6f41419a1d44e..0000000000000000000000000000000000000000 --- a/qml/components/DigitalDisplay.qml +++ /dev/null @@ -1,30 +0,0 @@ -import QtQuick 2.1 - -Rectangle { - - property alias title: displayTitle.text - property string textValue: "none" - - width: 110 - height: parent.height/3 - anchors.verticalCenter: parent.verticalCenter - border.color: "white" - - Text { - id:displayTitle - anchors.left: parent.left - anchors.leftMargin: 3 - anchors.verticalCenter: parent.verticalCenter - text: "blank" - color: "white" - } - - Text { - id:displayValue - anchors.right: parent.right - anchors.rightMargin: 3 - anchors.verticalCenter: parent.verticalCenter - text: textValue - color: "white" - } -} diff --git a/qml/components/StatusDisplay.qml b/qml/components/StatusDisplay.qml deleted file mode 100644 index 30bb8a848d9ac9cb31f99c36becefffcca8182bf..0000000000000000000000000000000000000000 --- a/qml/components/StatusDisplay.qml +++ /dev/null @@ -1,24 +0,0 @@ -import QtQuick 2.1 - -Rectangle { - id: statusDisplay - property alias statusText: armedText.text - property alias statusTextColor: armedText.color - property alias statusBackgroundColor: statusDisplay.color - - width: 100 - height: parent.height/3 - anchors.verticalCenter: parent.verticalCenter - radius: 3 - border.color: "white" - border.width: 1 - - Text { - id: armedText - anchors.centerIn: parent - verticalAlignment: Text.AlignVCenter - horizontalAlignment: Text.AlignHCenter - font.pixelSize: 20 - } - -} diff --git a/qml/components/TextButton.qml b/qml/components/TextButton.qml deleted file mode 100644 index 24b261cd95e5163c28c4477c5b0bcefb28325739..0000000000000000000000000000000000000000 --- a/qml/components/TextButton.qml +++ /dev/null @@ -1,70 +0,0 @@ -import QtQuick 2.1 - -Rectangle { - signal clicked - - property string label: "Text Button label" - property int minWidth: 75 - property int minHeight: 0 - property int margin: 5 - - width: textBox.width - height: 72 - anchors.verticalCenter: parent.verticalCenter - color: "black" - - signal buttonClick() - - onButtonClick: { - console.log(label + " clicked calling signal") - clicked() - } - - // Highlighting and ativation section - property color buttonColor: "black" - property color onHoverbuttonColor: "lightblue" - property color onHoverColor: "darkblue" - property color borderColor: "white" - - Rectangle { - width: textButtonLabel.paintedwidth - anchors.centerIn: parent - - Rectangle{ - id: textBox - anchors.centerIn: parent - width: minWidth > textButtonLabel.paintedWidth + margin ? minWidth : textButtonLabel.paintedWidth + margin - height: minHeight > textButtonLabel.paintedHeight + margin ? minHeight : textButtonLabel.paintedHeight + margin - - Text { - id: textButtonLabel - anchors.verticalCenter: parent.verticalCenter - anchors.horizontalCenter: parent.horizontalCenter - anchors.margins: 2 - text: label - color: "white" - font.pointSize: 11 - } - - MouseArea { - id: textButtonMouseArea - anchors.fill: parent - onClicked: buttonClick() - hoverEnabled: true - onEntered: { - parent.border.color = onHoverColor - parent.color = onHoverbuttonColor - } - onExited: { - parent.border.color = borderColor - parent.color = buttonColor - } - onPressed: parent.color = Qt.darker(onHoverbuttonColor, 1.5) - onReleased: parent.color = buttonColor - } - color: buttonColor - border.color: borderColor - border.width: 1 - } - } -} diff --git a/qml/resources/qgroundcontrol/toolbar/connect.png b/qml/resources/qgroundcontrol/toolbar/connect.png deleted file mode 100644 index 8572674974bcefde8dc4b54972a423a5a19837ff..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/connect.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/disconnect.png b/qml/resources/qgroundcontrol/toolbar/disconnect.png deleted file mode 100644 index 57f2f505da1eb32c90369f4fc9b154f7de5646f8..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/disconnect.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/donate.png b/qml/resources/qgroundcontrol/toolbar/donate.png deleted file mode 100644 index 80b1a14612ba76b405ec518f9c81148e6b24d28c..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/donate.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/flightdata.png b/qml/resources/qgroundcontrol/toolbar/flightdata.png deleted file mode 100644 index aa8fb3663f815da198374f57b40db001778dc462..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/flightdata.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/flightplanner.png b/qml/resources/qgroundcontrol/toolbar/flightplanner.png deleted file mode 100644 index 72e1b40ec8414bb24275b5f8d592b4284184e764..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/flightplanner.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/hardwareconfig.png b/qml/resources/qgroundcontrol/toolbar/hardwareconfig.png deleted file mode 100644 index 56fb5619310d64ab6b454779df81a7824c32fa63..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/hardwareconfig.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/helpwizard.png b/qml/resources/qgroundcontrol/toolbar/helpwizard.png deleted file mode 100644 index ac5c20a2a7c52fcb60a407c395919addf6202452..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/helpwizard.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/simulation.png b/qml/resources/qgroundcontrol/toolbar/simulation.png deleted file mode 100644 index e8a1c31a04ab6f9f9267abbf1c0bd08771ef97ce..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/simulation.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/softwareconfig.png b/qml/resources/qgroundcontrol/toolbar/softwareconfig.png deleted file mode 100644 index e2516db4060dee69ff7486243576d3749edfe97f..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/softwareconfig.png and /dev/null differ diff --git a/qml/resources/qgroundcontrol/toolbar/terminal.png b/qml/resources/qgroundcontrol/toolbar/terminal.png deleted file mode 100644 index bb639d3bd4c15454884a44cc664ca7585e99e3b7..0000000000000000000000000000000000000000 Binary files a/qml/resources/qgroundcontrol/toolbar/terminal.png and /dev/null differ diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 4a111c53ca7ea12744406285928e113a97b84dd0..4985d90463febdbe8ef7a885f764be514a7c2b87 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -25,7 +25,6 @@ #include "UASInterface.h" #include "UAS.h" #include "PxQuadMAV.h" -#include "ArduPilotMegaMAV.h" #include "configuration.h" #include "LinkManager.h" #include "QGCMAVLink.h" diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 248f7c84da699ed8649bd4429ffa8c3813ea9b30..de09f956f4177850a817e2df1e5fc9dd70eb58fb 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -585,28 +585,6 @@ void MAVLinkSimulationLink::mainloop() memcpy(stream+streampointer, buffer, bufferlength); streampointer += bufferlength; - - -// // HEARTBEAT VEHICLE 2 - -// // Pack message and get size of encoded byte string -// mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA); -// // Allocate buffer with packet data -// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); -// //add data into datastream -// memcpy(stream+streampointer,buffer, bufferlength); -// streampointer += bufferlength; - -// // HEARTBEAT VEHICLE 3 - -// // Pack message and get size of encoded byte string -// mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK); -// // Allocate buffer with packet data -// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); -// //add data into datastream -// memcpy(stream+streampointer,buffer, bufferlength); -// streampointer += bufferlength; - // Pack message and get size of encoded byte string mavlink_msg_sys_status_encode(54, componentId, &msg, &status); // Allocate buffer with packet data diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index e9c4624831476cbea849284f2f34288542953541..af12867dd26344cabe9c49d8a5feb62fb068bc4b 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -72,7 +72,7 @@ void MAVLinkSimulationMAV::mainloop() // 1 Hz execution if (timer1Hz <= 0) { mavlink_message_t msg; - mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE); + mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE); link->sendMAVLinkMessage(&msg); planner.handleMessage(msg); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 9734652447e185f2f571913bb6691849cf29c207..4a879fb328352a8f01e1e7a27d6ae13db2d3fdd6 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -117,14 +117,16 @@ bool SerialLink::isBootloader() foreach (const QSerialPortInfo &info, portList) { + // XXX debug statements will be removed once we have 100% stable link reports // qDebug() << "PortName : " << info.portName() // << "Description : " << info.description(); // qDebug() << "Manufacturer: " << info.manufacturer(); if (info.portName().trimmed() == this->m_portName.trimmed() && (info.description().toLower().contains("bootloader") || - info.description().toLower().contains("px4 bl"))) { - qDebug() << "BOOTLOADER FOUND"; + info.description().toLower().contains("px4 bl") || + info.description().toLower().contains("px4 fmu v1.6"))) { +// qDebug() << "BOOTLOADER FOUND"; return true; } } @@ -232,10 +234,10 @@ void SerialLink::run() } // If there are too many errors on this link, disconnect. - if (isConnected() && (linkErrorCount > 100)) { + if (isConnected() && (linkErrorCount > 150)) { qDebug() << "linkErrorCount too high: re-connecting!"; linkErrorCount = 0; - emit communicationUpdate(getName(), tr("Reconnecting on too many link errors")); + emit communicationUpdate(getName(), tr("Link timeout, not receiving any data, attempting reconnect")); if (m_port) { m_port->close(); @@ -266,10 +268,11 @@ void SerialLink::run() if (m_transmitBuffer.count() > 0) { m_writeMutex.lock(); int numWritten = m_port->write(m_transmitBuffer); - bool txSuccess = m_port->waitForBytesWritten(5); + bool txSuccess = m_port->flush(); + txSuccess |= m_port->waitForBytesWritten(10); if (!txSuccess || (numWritten != m_transmitBuffer.count())) { linkErrorCount++; - qDebug() << "TX Error! wrote" << numWritten << ", asked for " << m_transmitBuffer.count() << "bytes"; + qDebug() << "TX Error! written:" << txSuccess << "wrote" << numWritten << ", asked for " << m_transmitBuffer.count() << "bytes"; } else { @@ -290,7 +293,7 @@ void SerialLink::run() //wait n msecs for data to be ready //[TODO][BB] lower to SerialLink::poll_interval? m_dataMutex.lock(); - bool success = m_port->waitForReadyRead(10); + bool success = m_port->waitForReadyRead(20); if (success) { QByteArray readData = m_port->readAll(); @@ -416,6 +419,8 @@ bool SerialLink::disconnect() } wait(); // This will terminate the thread and close the serial port + emit connected(false); + emit disconnected(); return true; } diff --git a/src/qgcunittest/FlightModeConfigTest.cc b/src/qgcunittest/FlightModeConfigTest.cc deleted file mode 100644 index d0b01ff49808bea8881b4b48663c859e0fb77c14..0000000000000000000000000000000000000000 --- a/src/qgcunittest/FlightModeConfigTest.cc +++ /dev/null @@ -1,306 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -#include "FlightModeConfigTest.h" -#include "FlightModeConfig.h" -#include "UASManager.h" -#include "MockQGCUASParamManager.h" - -/// @file -/// @brief FlightModeConfig unit test -/// -/// @author Don Gagne - -FlightModeConfigUnitTest::FlightModeConfigUnitTest(void) : - _mockUASManager(NULL) -{ - -} - -void FlightModeConfigUnitTest::init(void) -{ - _mockUASManager = new MockUASManager(); - Q_ASSERT(_mockUASManager); - - UASManager::setMockUASManager(_mockUASManager); - - _mockUAS = new MockUAS(); - Q_ASSERT(_mockUAS); -} - -void FlightModeConfigUnitTest::cleanup(void) -{ - Q_ASSERT(_mockUAS); - delete _mockUAS; - - UASManager::setMockUASManager(NULL); - - Q_ASSERT(_mockUASManager); - delete _mockUASManager; -} - -void FlightModeConfigUnitTest::_nullUAS_test(void) -{ - // When there is no UAS the widget should be disabled - FlightModeConfig* fmc = new FlightModeConfig(); - QCOMPARE(fmc->isEnabled(), false); -} - -void FlightModeConfigUnitTest::_validUAS_test(void) -{ - // With an active UAS widget should be enabled - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - QCOMPARE(fmc->isEnabled(), true); -} - -void FlightModeConfigUnitTest::_nullToValidUAS_test(void) -{ - // start with no UAS - FlightModeConfig* fmc = new FlightModeConfig(); - - // clear it out and validate widget gets disabled - _mockUASManager->setMockActiveUAS(NULL); - QCOMPARE(fmc->isEnabled(), false); -} - -void FlightModeConfigUnitTest::_simpleModeFixedWing_test(void) -{ - // Fixed wing does not have simple mode, all checkboxes should be disabled - _mockUAS->setMockSystemType(MAV_TYPE_FIXED_WING); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - for (size_t i=0; i<_cCombo; i++) { - QCOMPARE(_rgSimpleModeCheckBox[i]->isEnabled(), false); - } -} - -void FlightModeConfigUnitTest::_simpleModeRover_test(void) -{ - // Rover does not have simple mode, all checkboxes should be disabled - _mockUAS->setMockSystemType(MAV_TYPE_GROUND_ROVER); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - for (size_t i=0; i<_cCombo; i++) { - QCOMPARE(_rgSimpleModeCheckBox[i]->isEnabled(), false); - } -} - -void FlightModeConfigUnitTest::_simpleModeRotor_test(void) -{ - // Rotor has simple mode, all checkboxes should be enabled - _mockUAS->setMockSystemType(MAV_TYPE_QUADROTOR); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - for (size_t i=0; i<_cCombo; i++) { - QCOMPARE(_rgSimpleModeCheckBox[i]->isEnabled(), true); - } -} - -void FlightModeConfigUnitTest::_modeSwitchParam_test(void) -{ - _mockUAS->setMockSystemType(MAV_TYPE_QUADROTOR); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - const char* rgModeSwitchParam[_cCombo] = { "FLTMODE1", "FLTMODE2", "FLTMODE3", "FLTMODE4", "FLTMODE5", "FLTMODE6" }; - const int rgModeSwitchValue[_cCombo] = { 0, 2, 4, 6, 8, 10 }; - - MockQGCUASParamManager::ParamMap_t mapParams; - for (size_t i=0; i<_cCombo; i++) { - mapParams[rgModeSwitchParam[i]] = QVariant(QChar(rgModeSwitchValue[i])); - } - - int simpleModeBitMask = 21; - mapParams["SIMPLE"] = QVariant(QChar(simpleModeBitMask)); - _mockUAS->setMockParametersAndSignal(mapParams); - - // Check that the UI is showing the correct information - for (size_t i=0; i<_cCombo; i++) { - QComboBox* combo = _rgCombo[i]; - - // Check for the correct selection in the combo boxes. Combo boxes store the mode - // in the item data, so use that to compare - QCOMPARE(combo->itemData(combo->currentIndex()), mapParams[rgModeSwitchParam[i]]); - - // Make sure the text for the current selection doesn't contain the text Unknown - // which means that it received an unsupported mode - QCOMPARE(combo->currentText().contains("unknown", Qt::CaseInsensitive), false); - - // Check that the right simple mode check boxes are checked - QCOMPARE(_rgSimpleModeCheckBox[i]->isChecked(), !!((1 << i) & simpleModeBitMask)); - } - - - // Click Save button and make sure we get the same values back through setParameter calls - QTest::mouseClick(_saveButton, Qt::LeftButton); - MockQGCUASParamManager* paramMgr = _mockUAS->getMockQGCUASParamManager(); - MockQGCUASParamManager::ParamMap_t mapParamsSet = paramMgr->getMockSetParameters(); - QMapIterator i(mapParams); - while (i.hasNext()) { - i.next(); - QCOMPARE(mapParamsSet.contains(i.key()), true); - int receivedValue = mapParamsSet[i.key()].toInt(); - int expectedValue = i.value().toInt(); - QCOMPARE(receivedValue, expectedValue); - } -} - -void FlightModeConfigUnitTest::_pwmTestWorker(int systemType, int modeSwitchChannel, const char* modeSwitchParam) -{ - _mockUAS->setMockSystemType(systemType); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - MockQGCUASParamManager::ParamMap_t mapParams; - if (modeSwitchParam != NULL) { - // Param is 1-based, code in here is all 0-base - mapParams[modeSwitchParam] = QVariant(QChar(modeSwitchChannel+1)); - _mockUAS->setMockParametersAndSignal(mapParams); - } - - const int pwmBoundary[] = { 1230, 1360, 1490, 1620, 1749, 1900 }; - - int lowerPWM = 0; - for (size_t i=0; i<_cCombo; i++) { - // emit a PWM value at the mid point of the switch position - int pwmMidPoint = ((pwmBoundary[i] - lowerPWM) / 2) + lowerPWM; - _mockUAS->emitRemoteControlChannelRawChanged(modeSwitchChannel, pwmMidPoint); - - // Make sure that only the correct pwm label has a style set on it for highlight - for (size_t j=0; j<_cCombo; j++) { - if (j == i) { - QVERIFY(_rgPWMLabel[j]->styleSheet().length() > 0); - } else { - QCOMPARE(_rgPWMLabel[j]->styleSheet().length(), 0); - } - } - - lowerPWM = pwmBoundary[i]; - } -} - -void FlightModeConfigUnitTest::_pwmFixedWing_test(void) -{ - // FixedWing has mode switch channel on FLTMODE_CH param - _pwmTestWorker(MAV_TYPE_FIXED_WING, 7, "FLTMODE_CH"); -} - -void FlightModeConfigUnitTest::_pwmRotor_test(void) -{ - // Rotor is hardwired to 0-based rc channel 4 for mode wsitch - _pwmTestWorker(MAV_TYPE_QUADROTOR, 4, NULL); -} - -void FlightModeConfigUnitTest::_pwmRover_test(void) -{ - // Rover has mode switch channel on MODE_CH param - _pwmTestWorker(MAV_TYPE_GROUND_ROVER, 7, "MODE_CH"); -} - -void FlightModeConfigUnitTest::_pwmInvalidChannel_test(void) -{ - // Rover has mode switch channel on MODE_CH param - _mockUAS->setMockSystemType(MAV_TYPE_GROUND_ROVER); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - int modeSwitchChannel = 7; - MockQGCUASParamManager::ParamMap_t mapParams; - mapParams["MODE_CH"] = QVariant(QChar(modeSwitchChannel+1)); // 1-based - _mockUAS->setMockParametersAndSignal(mapParams); - - const int pwmBoundary[] = { 1230, 1360, 1490, 1620, 1749, 1900 }; - - int lowerPWM = 0; - for (size_t i=0; i<_cCombo; i++) { - // emit a PWM value at the mid point of the switch position - int pwmMidPoint = ((pwmBoundary[i] - lowerPWM) / 2) + lowerPWM; - // emit rc values on wrong channel - _mockUAS->emitRemoteControlChannelRawChanged(modeSwitchChannel-1, pwmMidPoint); - - // Make sure no label have a style set on it for highlight - for (size_t j=0; j<_cCombo; j++) { - QCOMPARE(_rgPWMLabel[j]->styleSheet().length(), 0); - } - - lowerPWM = pwmBoundary[i]; - } -} - -void FlightModeConfigUnitTest::_unknownSystemType_test(void) -{ - // Set the system type to something we can't handle, make sure we are disabled - _mockUAS->setMockSystemType(MAV_TYPE_ENUM_END); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - QCOMPARE(fmc->isEnabled(), false); -} - -void FlightModeConfigUnitTest::_unknownMode_test(void) -{ - _mockUAS->setMockSystemType(MAV_TYPE_QUADROTOR); - _mockUASManager->setMockActiveUAS(_mockUAS); - FlightModeConfig* fmc = new FlightModeConfig(); - _findControls(fmc); - - // Set an unknown mode - MockQGCUASParamManager::ParamMap_t mapParams; - mapParams["FLTMODE1"] = QVariant(QChar(100)); - _mockUAS->setMockParametersAndSignal(mapParams); - - // Check for the correct selection in the combo boxes. Combo boxes store the mode - // in the item data, so use that to compare - QCOMPARE(_rgCombo[0]->itemData(_rgCombo[0]->currentIndex()), mapParams["FLTMODE1"]); - - // Make sure the text for the current selection contains the text Unknown - QCOMPARE(_rgCombo[0]->currentText().contains("unknown", Qt::CaseInsensitive), true); -} - -void FlightModeConfigUnitTest::_findControls(QObject* fmc) -{ - // Find all the controls - for (size_t i=0; i<_cCombo; i++) { - _rgLabel[i] = fmc->findChild(QString("mode%1Label").arg(i)); - _rgCombo[i] = fmc->findChild(QString("mode%1ComboBox").arg(i)); - _rgSimpleModeCheckBox[i] = fmc->findChild(QString("mode%1SimpleCheckBox").arg(i)); - _rgPWMLabel[i] = fmc->findChild(QString("mode%1PWMLabel").arg(i)); - Q_ASSERT(_rgLabel[i]); - Q_ASSERT(_rgCombo[i]); - Q_ASSERT(_rgSimpleModeCheckBox[i]); - Q_ASSERT(_rgPWMLabel[i]); - } - - _saveButton = fmc->findChild("savePushButton"); - Q_ASSERT(_saveButton); -} - diff --git a/src/qgcunittest/FlightModeConfigTest.h b/src/qgcunittest/FlightModeConfigTest.h deleted file mode 100644 index 89b5d38f8c36ad4b65edf4819a0f85c76065aa84..0000000000000000000000000000000000000000 --- a/src/qgcunittest/FlightModeConfigTest.h +++ /dev/null @@ -1,87 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -#ifndef FLIGHTMODECONFIGTEST_H -#define FLIGHTMODECONFIGTEST_H - -#include "AutoTest.h" -#include "MockUASManager.h" -#include "MockUAS.h" -#include -#include -#include -#include -#include - -class FlightModeConfig; - -/// @file -/// @brief FlightModeConfig unit test -/// -/// @author Don Gagne - -class FlightModeConfigUnitTest : public QObject -{ - Q_OBJECT - -public: - FlightModeConfigUnitTest(void); - -private slots: - void init(void); - void cleanup(void); - - void _nullUAS_test(void); - void _validUAS_test(void); - void _nullToValidUAS_test(void); - void _simpleModeFixedWing_test(void); - void _simpleModeRover_test(void); - void _simpleModeRotor_test(void); - void _modeSwitchParam_test(void); - void _pwmFixedWing_test(void); - void _pwmRotor_test(void); - void _pwmRover_test(void); - void _pwmInvalidChannel_test(void); - void _unknownSystemType_test(void); - void _unknownMode_test(void); - -private: - void _findControls(QObject* fmc); - void _pwmTestWorker(int systemType, int modeSwitchChannel, const char* modeSwitchParam); - -private: - MockUASManager* _mockUASManager; - MockUAS* _mockUAS; - - // FlightModeConfig ui elements - static const size_t _cCombo = 6; - QLabel* _rgLabel[_cCombo]; - QComboBox* _rgCombo[_cCombo]; - QCheckBox* _rgSimpleModeCheckBox[_cCombo]; - QLabel* _rgPWMLabel[_cCombo]; - QPushButton* _saveButton; -}; - -DECLARE_TEST(FlightModeConfigUnitTest) - -#endif diff --git a/src/uas/ArduPilotMegaMAV.cc b/src/uas/ArduPilotMegaMAV.cc deleted file mode 100644 index e8b61c697accd67774ba4a50c683dcd5aa234c3c..0000000000000000000000000000000000000000 --- a/src/uas/ArduPilotMegaMAV.cc +++ /dev/null @@ -1,132 +0,0 @@ -/*===================================================================== -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Implementation of class MainWindow - * @author Your Name here - */ - -#include "ArduPilotMegaMAV.h" - -#ifdef QGC_USE_ARDUPILOTMEGA_MESSAGES -#ifndef MAVLINK_MSG_ID_MOUNT_CONFIGURE -#include "ardupilotmega/mavlink_msg_mount_configure.h" -#endif - -#ifndef MAVLINK_MSG_ID_MOUNT_CONTROL -#include "ardupilotmega/mavlink_msg_mount_control.h" -#endif -#endif - -ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, QThread* thread, int id) : - UAS(mavlink, thread, id)//, - // place other initializers here -{ - //This does not seem to work. Manually request each stream type at a specified rate. - // Ask for all streams at 4 Hz - //enableAllDataTransmission(4); - txReqTimer = new QTimer(this); - connect(txReqTimer,SIGNAL(timeout()),this,SLOT(sendTxRequests())); - - QTimer::singleShot(5000,this,SLOT(sendTxRequests())); //Send an initial TX request in 5 seconds. - - txReqTimer->start(300000); //Resend the TX requests every 5 minutes. -} -void ArduPilotMegaMAV::sendTxRequests() -{ - enableExtendedSystemStatusTransmission(2); - QGC::SLEEP::msleep(250); - enablePositionTransmission(3); - QGC::SLEEP::msleep(250); - enableExtra1Transmission(10); - QGC::SLEEP::msleep(250); - enableExtra2Transmission(10); - QGC::SLEEP::msleep(250); - enableExtra3Transmission(2); - QGC::SLEEP::msleep(250); - enableRawSensorDataTransmission(2); - QGC::SLEEP::msleep(250); - enableRCChannelDataTransmission(2); -} - -/** - * This function is called by MAVLink once a complete, uncorrupted (CRC check valid) - * mavlink packet is received. - * - * @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port). - * messages can be sent back to the system via this link - * @param message MAVLink message, as received from the MAVLink protocol stack - */ -void ArduPilotMegaMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) -{ - // Let UAS handle the default message set - UAS::receiveMessage(link, message); - - if (message.sysid == uasId) { - // Handle your special messages - switch (message.msgid) { - case MAVLINK_MSG_ID_HEARTBEAT: - { - //qDebug() << "ARDUPILOT RECEIVED HEARTBEAT"; - break; - } - default: - //qDebug() << "\nARDUPILOT RECEIVED MESSAGE WITH ID" << message.msgid; - break; - } - } -} -void ArduPilotMegaMAV::setMountConfigure(unsigned char mode, bool stabilize_roll,bool stabilize_pitch,bool stabilize_yaw) -{ -#ifdef QGC_USE_ARDUPILOTMEGA_MESSAGES - //Only supported by APM - mavlink_message_t msg; - mavlink_msg_mount_configure_pack(255,1,&msg,this->uasId,1,mode,stabilize_roll,stabilize_pitch,stabilize_yaw); - sendMessage(msg); -#else - Q_UNUSED(mode); - Q_UNUSED(stabilize_roll); - Q_UNUSED(stabilize_pitch); - Q_UNUSED(stabilize_yaw); -#endif -} -void ArduPilotMegaMAV::setMountControl(double pa,double pb,double pc,bool islatlong) -{ -#ifdef QGC_USE_ARDUPILOTMEGA_MESSAGES - mavlink_message_t msg; - if (islatlong) - { - mavlink_msg_mount_control_pack(255,1,&msg,this->uasId,1,pa*10000000.0,pb*10000000.0,pc*10000000.0,0); - } - else - { - mavlink_msg_mount_control_pack(255,1,&msg,this->uasId,1,pa,pb,pc,0); - } - sendMessage(msg); -#else - Q_UNUSED(pa); - Q_UNUSED(pb); - Q_UNUSED(pc); - Q_UNUSED(islatlong); -#endif -} diff --git a/src/uas/ArduPilotMegaMAV.h b/src/uas/ArduPilotMegaMAV.h deleted file mode 100644 index 1ff5bf57ebb1622b426c65f98948cd8c2a6d94bc..0000000000000000000000000000000000000000 --- a/src/uas/ArduPilotMegaMAV.h +++ /dev/null @@ -1,45 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -#ifndef ARDUPILOTMEGAMAV_H -#define ARDUPILOTMEGAMAV_H - -#include "UAS.h" -class ArduPilotMegaMAV : public UAS -{ - Q_OBJECT -public: - ArduPilotMegaMAV(MAVLinkProtocol* mavlink, QThread* thread, int id = 0); - /** @brief Set camera mount stabilization modes */ - void setMountConfigure(unsigned char mode, bool stabilize_roll,bool stabilize_pitch,bool stabilize_yaw); - /** @brief Set camera mount control */ - void setMountControl(double pa,double pb,double pc,bool islatlong); -public slots: - /** @brief Receive a MAVLink message from this MAV */ - void receiveMessage(LinkInterface* link, mavlink_message_t message); - void sendTxRequests(); -private: - QTimer *txReqTimer; -}; - -#endif // ARDUPILOTMAV_H diff --git a/src/uas/QGCMAVLinkUASFactory.cc b/src/uas/QGCMAVLinkUASFactory.cc index a934e965b6e1410bbe9d4586663c177e7075e9ff..05620ff037357e1f7edd70c7fd7097464b41abfb 100644 --- a/src/uas/QGCMAVLinkUASFactory.cc +++ b/src/uas/QGCMAVLinkUASFactory.cc @@ -67,21 +67,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte uas = px4; } break; - // XXX the APM support needs polishing before it can be shown to users -// case MAV_AUTOPILOT_ARDUPILOTMEGA: -// { -// ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, worker, sysid); -// // Set the system type -// mav->setSystemType((int)heartbeat->type); - -// // Connect this robot to the UAS object -// // it is IMPORTANT here to use the right object type, -// // else the slot of the parent object is called (and thus the special -// // packets never reach their goal) -// connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t))); -// uas = mav; -// } -// break; #ifdef QGC_USE_SENSESOAR_MESSAGES case MAV_AUTOPILOT_SENSESOAR: { diff --git a/src/uas/QGCMAVLinkUASFactory.h b/src/uas/QGCMAVLinkUASFactory.h index d050a3384ec05e911a150b7838f496478af693ca..9c15a3f21c7a912ef159c16e6510c0c6a9a7603f 100644 --- a/src/uas/QGCMAVLinkUASFactory.h +++ b/src/uas/QGCMAVLinkUASFactory.h @@ -12,7 +12,6 @@ #include "UAS.h" #include "PxQuadMAV.h" #include "senseSoarMAV.h" -#include "ArduPilotMegaMAV.h" class QGCMAVLinkUASFactory : public QObject { diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 692d1b1fab42ee6b13a56609efdb596e0ea2419f..569d3307574e21da449614bad0a4ac90d9261e04 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -497,27 +497,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // Set new type if it has changed if (this->type != state.type) { - this->type = state.type; - if (airframe == 0) - { - switch (type) - { - case MAV_TYPE_FIXED_WING: - setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR); - break; - case MAV_TYPE_QUADROTOR: - setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH); - break; - case MAV_TYPE_HEXAROTOR: - setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER); - break; - default: - // Do nothing - break; - } - } this->autopilot = state.autopilot; - emit systemTypeSet(this, type); + setSystemType(state.type); } bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY; @@ -1316,7 +1297,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) if (text.startsWith("#") || severity <= MAV_SEVERITY_WARNING) { text.remove("#audio:"); - emit textMessageReceived(uasId, message.compid, severity, QString("Audio message: ") + text); + emit textMessageReceived(uasId, message.compid, severity, text); GAudioOutput::instance()->say(text.toLower(), severity); } else @@ -2593,17 +2574,25 @@ void UAS::setSystemType(int systemType) // If the airframe is still generic, change it to a close default type if (airframe == 0) { - switch (systemType) + switch (type) { case MAV_TYPE_FIXED_WING: - airframe = QGC_AIRFRAME_EASYSTAR; + setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR); break; case MAV_TYPE_QUADROTOR: - airframe = QGC_AIRFRAME_MIKROKOPTER; + setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH); + break; + case MAV_TYPE_HEXAROTOR: + setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER); + break; + default: + // Do nothing break; } } emit systemSpecsChanged(uasId); + emit systemTypeSet(this, type); + qDebug() << "TYPE CHANGED TO:" << type; } } diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index f59b5bbdb82c991f46e9c037a8934076ef726e12..3ce913a1b841693bba52dcc758df8a7f72692a62 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -43,6 +43,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : messageFilter.insert(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, false); #endif messageFilter.insert(MAVLINK_MSG_ID_EXTENDED_MESSAGE, false); + messageFilter.insert(MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, false); textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false); textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG_VECT, false); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index c209145add77fca2e2dda0879ae7b1714c217d1a..115643343565a105885c6b4aa11c135630506ed9 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -64,9 +64,6 @@ This file is part of the QGROUNDCONTROL project #include "QGCTabbedInfoView.h" #include "UASRawStatusView.h" #include "PrimaryFlightDisplay.h" -#include -#include -#include #include #include "SerialSettingsDialog.h" #include "terminalconsole.h" @@ -205,31 +202,27 @@ void MainWindow::init() // Load Toolbar - if (!(getCustomMode() == CUSTOM_MODE_APM)) { - toolBar = new QGCToolBar(this); - this->addToolBar(toolBar); - - // Add actions for average users (displayed next to each other) - QList actions; - actions << ui.actionMissionView; - actions << ui.actionFlightView; - actions << ui.actionHardwareConfig; - - toolBar->setPerspectiveChangeActions(actions); - - // Add actions for advanced users (displayed in dropdown under "advanced") - QList advancedActions; - advancedActions << ui.actionEngineersView; - advancedActions << ui.actionGoogleEarthView; - advancedActions << ui.actionLocal3DView; - advancedActions << ui.actionSoftwareConfig; - advancedActions << ui.actionTerminalView; - advancedActions << ui.actionSimulationView; - - toolBar->setPerspectiveChangeAdvancedActions(advancedActions); - } else { - ui.actionHardwareConfig->setText(tr("Hardware")); - } + toolBar = new QGCToolBar(this); + this->addToolBar(toolBar); + + // Add actions for average users (displayed next to each other) + QList actions; + actions << ui.actionMissionView; + actions << ui.actionFlightView; + actions << ui.actionHardwareConfig; + + toolBar->setPerspectiveChangeActions(actions); + + // Add actions for advanced users (displayed in dropdown under "advanced") + QList advancedActions; + advancedActions << ui.actionEngineersView; + advancedActions << ui.actionGoogleEarthView; + advancedActions << ui.actionLocal3DView; + advancedActions << ui.actionSoftwareConfig; + advancedActions << ui.actionTerminalView; + advancedActions << ui.actionSimulationView; + + toolBar->setPerspectiveChangeAdvancedActions(advancedActions); customStatusBar = new QGCStatusBar(this); setStatusBar(customStatusBar); @@ -255,28 +248,6 @@ void MainWindow::init() connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addLink(LinkInterface*))); - if (getCustomMode() == CUSTOM_MODE_APM) { - // Add the APM 'toolbar' - - APMToolBar *apmToolBar = new APMToolBar(); - apmToolBar->setFlightViewAction(ui.actionFlightView); - apmToolBar->setFlightPlanViewAction(ui.actionMissionView); - apmToolBar->setHardwareViewAction(ui.actionHardwareConfig); - apmToolBar->setSoftwareViewAction(ui.actionSoftwareConfig); - apmToolBar->setSimulationViewAction(ui.actionSimulationView); - apmToolBar->setTerminalViewAction(ui.actionTerminalView); - - QDockWidget *widget = new QDockWidget(tr("APM Tool Bar"),this); - QWidget *toolbarWidget = QWidget::createWindowContainer(apmToolBar, this); - widget->setWidget(toolbarWidget); - widget->setMinimumHeight(72); - widget->setMaximumHeight(72); - widget->setMinimumWidth(1024); - widget->setFeatures(QDockWidget::NoDockWidgetFeatures); - widget->setTitleBarWidget(new QWidget(this)); // Disables the title bar - this->addDockWidget(Qt::TopDockWidgetArea, widget); - } - // Connect user interface devices emit initStatusChanged(tr("Initializing joystick interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); joystick = new JoystickInput(); @@ -559,31 +530,12 @@ void MainWindow::buildCommonWidgets() addToCentralStackedWidget(terminalView, VIEW_TERMINAL, tr("Terminal View")); } - if (getCustomMode() == CUSTOM_MODE_APM) { - if (!configView) - { - configView = new SubMainWindow(this); - configView->setObjectName("VIEW_HARDWARE_CONFIG"); - configView->setCentralWidget(new ApmHardwareConfig(this)); - addToCentralStackedWidget(configView, VIEW_HARDWARE_CONFIG, "Hardware"); - - } - if (!softwareConfigView) - { - softwareConfigView = new SubMainWindow(this); - softwareConfigView->setObjectName("VIEW_SOFTWARE_CONFIG"); - softwareConfigView->setCentralWidget(new ApmSoftwareConfig(this)); - addToCentralStackedWidget(softwareConfigView, VIEW_SOFTWARE_CONFIG, "Software"); - } - - } else { - if (!configView) - { - configView = new SubMainWindow(this); - configView->setObjectName("VIEW_HARDWARE_CONFIG"); - configView->setCentralWidget(new QGCConfigView(this)); - addToCentralStackedWidget(configView, VIEW_HARDWARE_CONFIG, "Config"); - } + if (!configView) + { + configView = new SubMainWindow(this); + configView->setObjectName("VIEW_HARDWARE_CONFIG"); + configView->setCentralWidget(new QGCConfigView(this)); + addToCentralStackedWidget(configView, VIEW_HARDWARE_CONFIG, "Config"); } if (!engineeringView) @@ -1209,14 +1161,12 @@ void MainWindow::connectCommonActions() perspectives->addAction(ui.actionSimulationView); perspectives->addAction(ui.actionMissionView); perspectives->addAction(ui.actionHardwareConfig); - perspectives->addAction(ui.actionSoftwareConfig); perspectives->addAction(ui.actionTerminalView); perspectives->addAction(ui.actionGoogleEarthView); perspectives->addAction(ui.actionLocal3DView); perspectives->setExclusive(true); /* Hide the actions that are not relevant */ - ui.actionSoftwareConfig->setVisible(getCustomMode() == CUSTOM_MODE_APM); #ifndef QGC_GOOGLE_EARTH_ENABLED ui.actionGoogleEarthView->setVisible(false); #endif @@ -1617,7 +1567,7 @@ void MainWindow::UASCreated(UASInterface* uas) watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET"); } } - + // Reload view state in case new widgets were added loadViewState(); } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 5cfdec60aa5dcc9596a00284a57e081833c777a5..96326b820e3710b8cbe34244bd14668b4dcda761 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -98,7 +98,6 @@ public: CUSTOM_MODE_UNCHANGED = 0, CUSTOM_MODE_NONE, CUSTOM_MODE_PX4, - CUSTOM_MODE_APM, CUSTOM_MODE_WIFI }; diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index c8c3f1ae14814024a8c34327e8fdb5b71a89a55f..20ca485ebd469fb4c9ed376ad3d38b96eb48b29b 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -51,7 +51,7 @@ 0 0 1024 - 21 + 22 @@ -100,7 +100,6 @@ - diff --git a/src/ui/PrimaryFlightDisplay.cc b/src/ui/PrimaryFlightDisplay.cc index 38e0654d9c0b11e7ee4b8c2f8ed02048e6a81c60..94a1e6cfa586dd17573a39281380f06007eedb07 100644 --- a/src/ui/PrimaryFlightDisplay.cc +++ b/src/ui/PrimaryFlightDisplay.cc @@ -453,7 +453,7 @@ void PrimaryFlightDisplay::drawTextCenterBottom ( font.setPixelSize(pixelSize); painter.setFont(font); - QFontMetrics metrics = QFontMetrics(font); + QFontMetrics metrics(font); QRect bounds = metrics.boundingRect(text); int flags = Qt::AlignCenter; painter.drawText(x - bounds.width()/2, y, bounds.width(), bounds.height(), flags, text); diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index 5b540ed617925b916bcf4651b17792df592fc973..88aa88f9670192ab567c4959b4add069b1799136 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -25,9 +25,7 @@ #include "px4_configuration/QGCPX4SensorCalibration.h" #include "px4_configuration/PX4RCCalibration.h" -#ifdef QGC_QUPGRADE_ENABLED -#include -#endif +#include "PX4FirmwareUpgrade.h" #define WIDGET_INDEX_FIRMWARE 0 #define WIDGET_INDEX_RC 1 @@ -67,18 +65,8 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : px4RCCalibration = new PX4RCCalibration(this); ui->rcLayout->addWidget(px4RCCalibration); -#ifdef QGC_QUPGRADE_ENABLED - DialogBare *firmwareDialog = new DialogBare(this); - ui->firmwareLayout->addWidget(firmwareDialog); - - connect(firmwareDialog, SIGNAL(connectLinks()), LinkManager::instance(), SLOT(connectAll())); - connect(firmwareDialog, SIGNAL(disconnectLinks()), LinkManager::instance(), SLOT(disconnectAll())); -#else - - QLabel* label = new QLabel(this); - label->setText("THIS VERSION OF QGROUNDCONTROL WAS BUILT WITHOUT QUPGRADE. To enable firmware upload support, checkout QUpgrade WITHIN the QGroundControl folder"); - ui->firmwareLayout->addWidget(label); -#endif + PX4FirmwareUpgrade* firmwareUpgrade = new PX4FirmwareUpgrade(this); + ui->firmwareLayout->addWidget(firmwareUpgrade); connect(ui->rcMenuButton,SIGNAL(clicked()), this,SLOT(rcMenuButtonClicked())); @@ -278,10 +266,6 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName(); - //Load configuration after 1ms. This allows it to go into the event loop, and prevents application hangups due to the - //amount of time it actually takes to load the configuration windows. - QTimer::singleShot(1,this,SLOT(loadConfig())); - updateStatus(QString("Reading from system %1").arg(mav->getUASName())); // Since a system is now connected, enable the VehicleConfig UI. diff --git a/src/ui/QGCToolBar.cc b/src/ui/QGCToolBar.cc index 38ae649fc3c704460f83fc7508652ac271e83a0f..f8dec1b73c14c9fae54196969e243f0ab82a1489 100644 --- a/src/ui/QGCToolBar.cc +++ b/src/ui/QGCToolBar.cc @@ -781,11 +781,17 @@ void QGCToolBar::connectLink(bool connect) link->setPortName(portComboBox->itemData(portComboBox->currentIndex()).toString().trimmed()); int baud = baudcomboBox->currentText().toInt(); link->setBaudRate(baud); + QObject::connect(link, SIGNAL(connected(bool)), this, SLOT(updateLinkState(bool))); link->connect(); } } else if (!connect && currentLink) { currentLink->disconnect(); + QObject::disconnect(currentLink, SIGNAL(connected(bool)), this, SLOT(updateLinkState(bool))); + } + + if (currentLink) { + updateLinkState(currentLink->isConnected()); } } diff --git a/src/ui/apmtoolbar.cpp b/src/ui/apmtoolbar.cpp deleted file mode 100644 index 5a4589d2e04c1aa72997c8ae562471a6aac0ca7e..0000000000000000000000000000000000000000 --- a/src/ui/apmtoolbar.cpp +++ /dev/null @@ -1,215 +0,0 @@ -#include -#include -#include -#include -#include "LinkManager.h" -#include "MainWindow.h" - -#include "apmtoolbar.h" - -APMToolBar::APMToolBar(): - QQuickView(), m_uas(0) -{ - // Configure our QML object - - // Hack to fix QTBUG 34300 on OSX where QDir::currentPath has changed behavior. This causes - // relative paths to inside the .app package to fail. -#ifdef Q_OS_MAC - QString qmlFile = QApplication::applicationDirPath(); - qmlFile.append("/qml/ApmToolBar.qml"); - setSource(QUrl::fromLocalFile(qmlFile)); -#else - setSource(QUrl::fromLocalFile("qml/ApmToolBar.qml")); -#endif - setResizeMode(QQuickView::SizeRootObjectToView); - rootContext()->setContextProperty("globalObj", this); - connect(LinkManager::instance(),SIGNAL(newLink(LinkInterface*)), - this, SLOT(updateLinkDisplay(LinkInterface*))); - - if (LinkManager::instance()->getLinks().count()>=3) { - updateLinkDisplay(LinkManager::instance()->getLinks().last()); - } - - setConnection(false); - - connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUasSet(UASInterface*))); - activeUasSet(UASManager::instance()->getActiveUAS()); -} -void APMToolBar::activeUasSet(UASInterface *uas) -{ - if (!uas) - { - return; - } - if (m_uas) - { - disconnect(m_uas,SIGNAL(armingChanged(bool)), - this,SLOT(armingChanged(bool))); - disconnect(uas,SIGNAL(armingChanged(int, QString)), - this,SLOT(armingChanged(int, QString))); - } - connect(uas,SIGNAL(armingChanged(bool)), - this,SLOT(armingChanged(bool))); - connect(uas,SIGNAL(armingChanged(int, QString)), - this,SLOT(armingChanged(int, QString))); - -} -void APMToolBar::armingChanged(bool armed) -{ - rootObject()->setProperty("armed", armed); -} - -void APMToolBar::armingChanged(int sysId, QString armingState) -{ - qDebug() << "APMToolBar: sysid " << sysId << " armState" << armingState; -} - -void APMToolBar::setFlightViewAction(QAction *action) -{ - connect(this, SIGNAL(triggerFlightView()), action, SIGNAL(triggered())); -} - -void APMToolBar::setFlightPlanViewAction(QAction *action) -{ - connect(this, SIGNAL(triggerFlightPlanView()), action, SIGNAL(triggered())); -} - -void APMToolBar::setHardwareViewAction(QAction *action) -{ - connect(this, SIGNAL(triggerHardwareView()), action, SIGNAL(triggered())); -} - -void APMToolBar::setSoftwareViewAction(QAction *action) -{ - connect(this, SIGNAL(triggerSoftwareView()), action, SIGNAL(triggered())); -} - -void APMToolBar::setSimulationViewAction(QAction *action) -{ - connect(this, SIGNAL(triggerSimulationView()), action, SIGNAL(triggered())); -} - -void APMToolBar::setTerminalViewAction(QAction *action) -{ - connect(this, SIGNAL(triggerTerminalView()), action, SIGNAL(triggered())); -} - -void APMToolBar::setConnectMAVAction(QAction *action) -{ - connect(this, SIGNAL(connectMAV()), action, SIGNAL(triggered())); -} - -void APMToolBar::selectFlightView() -{ - qDebug() << "APMToolBar: SelectFlightView"; - emit triggerFlightView(); -} - -void APMToolBar::selectFlightPlanView() -{ - qDebug() << "APMToolBar: SelectFlightPlanView"; - emit triggerFlightPlanView(); -} - -void APMToolBar::selectHardwareView() -{ - qDebug() << "APMToolBar: selectHardwareView"; - emit triggerHardwareView(); -} - -void APMToolBar::selectSoftwareView() -{ - qDebug() << "APMToolBar: selectSoftwareView"; - emit triggerSoftwareView(); -} - -void APMToolBar::selectSimulationView() -{ - qDebug() << "APMToolBar: selectSimulationView"; -} - -void APMToolBar::selectTerminalView() -{ - qDebug() << "APMToolBar: selectTerminalView"; -} - -void APMToolBar::connectMAV() -{ - qDebug() << "APMToolBar: connectMAV "; - - if (LinkManager::instance()->getSerialLinks().count() > 0) { - bool result; - bool connected = LinkManager::instance()->getSerialLinks().last()->isConnected(); - if (connected) { - // result need to be the opposite of success. - result = !LinkManager::instance()->getSerialLinks().last()->disconnect(); - } else { - // Need to Connect Link - result = LinkManager::instance()->getSerialLinks().last()->connect(); - } - qDebug() << "result = " << result; - - // Change the image to represent the state - setConnection(result); - - emit MAVConnected(result); - } else { - // No Link so prompt to connect one - MainWindow::instance()->addLink(); - } -} - -void APMToolBar::setConnection(bool connection) -{ - // Change the image to represent the state - rootObject()->setProperty("connected", connection); -} - -APMToolBar::~APMToolBar() -{ - qDebug() << "Destory APM Toolbar"; -} - -void APMToolBar::showConnectionDialog() -{ - // Displays a UI where the user can select a MAV Link. - qDebug() << "APMToolBar: showConnectionDialog link count =" - << LinkManager::instance()->getLinks().count(); - - bool result; - - if (LinkManager::instance()->getSerialLinks().count() > 0) - { - SerialLink *link = LinkManager::instance()->getSerialLinks().last(); - // Serial Link so prompt to config it - connect(link, SIGNAL(updateLink(LinkInterface*)), - this, SLOT(updateLinkDisplay(LinkInterface*))); - result = MainWindow::instance()->configLink(link); - - if (!result) - qDebug() << "Link Config Failed!"; - } else { - // No Link so prompt to create one - MainWindow::instance()->addLink(); - } - -} - -void APMToolBar::updateLinkDisplay(LinkInterface* newLink) -{ - qDebug() << "APMToolBar: updateLinkDisplay"; - QObject *object = rootObject(); - - if (newLink && rootObject()){ - qint64 baudrate = newLink->getConnectionSpeed(); - object->setProperty("baudrateLabel", QString::number(baudrate)); - - QString linkName = newLink->getName(); - object->setProperty("linkNameLabel", linkName); - - connect(newLink, SIGNAL(connected(bool)), - this, SLOT(setConnection(bool))); - - setConnection(newLink->isConnected()); - } -} diff --git a/src/ui/apmtoolbar.h b/src/ui/apmtoolbar.h deleted file mode 100644 index 5cb93d82c0337fc2dabac831c6dc9a9c1f2b2acc..0000000000000000000000000000000000000000 --- a/src/ui/apmtoolbar.h +++ /dev/null @@ -1,57 +0,0 @@ -#ifndef APMTOOLBAR_H -#define APMTOOLBAR_H - -#include -#include -#include "UASInterface.h" - -class LinkInterface; - -class APMToolBar : public QQuickView -{ - Q_OBJECT -public: - explicit APMToolBar(); - ~APMToolBar(); - - void setFlightViewAction(QAction *action); - void setFlightPlanViewAction(QAction *action); - void setHardwareViewAction(QAction *action); - void setSoftwareViewAction(QAction *action); - void setSimulationViewAction(QAction *action); - void setTerminalViewAction(QAction *action); - void setConnectMAVAction(QAction *action); - -signals: - void triggerFlightView(); - void triggerFlightPlanView(); - void triggerHardwareView(); - void triggerSoftwareView(); - void triggerSimulationView(); - void triggerTerminalView(); - - void MAVConnected(bool connected); - -public slots: - void selectFlightView(); - void selectFlightPlanView(); - void selectHardwareView(); - void selectSoftwareView(); - void selectSimulationView(); - void selectTerminalView(); - - void connectMAV(); - void showConnectionDialog(); - void setConnection(bool connection); - - void activeUasSet(UASInterface *uas); - void armingChanged(int sysId, QString armingState); - void armingChanged(bool armed); - - void updateLinkDisplay(LinkInterface *newLink); - -private: - UASInterface *m_uas; -}; - -#endif // APMTOOLBAR_H diff --git a/src/ui/configuration/AP2ConfigWidget.cc b/src/ui/configuration/AP2ConfigWidget.cc deleted file mode 100644 index d48158b3222d4a4b1e9c86200e7320b42fac81e8..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AP2ConfigWidget.cc +++ /dev/null @@ -1,36 +0,0 @@ -#include -#include "AP2ConfigWidget.h" - -AP2ConfigWidget::AP2ConfigWidget(QWidget *parent) : QWidget(parent) -{ - m_uas = 0; -} -void AP2ConfigWidget::initConnections() -{ - connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*))); - activeUASSet(UASManager::instance()->getActiveUAS()); -} - -void AP2ConfigWidget::activeUASSet(UASInterface *uas) -{ - if (m_uas) - { - disconnect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant))); - m_uas = 0; - } - if (!uas) return; - m_uas = uas; - connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant))); -} - -void AP2ConfigWidget::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - Q_UNUSED(parameterName); - Q_UNUSED(value); -} -void AP2ConfigWidget::showNullMAVErrorMessageBox() -{ - QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration")); -} diff --git a/src/ui/configuration/AP2ConfigWidget.h b/src/ui/configuration/AP2ConfigWidget.h deleted file mode 100644 index b8a397dd249e346f4a3d036692a3887382525db2..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AP2ConfigWidget.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef AP2CONFIGWIDGET_H -#define AP2CONFIGWIDGET_H - -#include -#include "UASManager.h" -#include "UASInterface.h" -class AP2ConfigWidget : public QWidget -{ - Q_OBJECT -public: - explicit AP2ConfigWidget(QWidget *parent = 0); -protected: - UASInterface *m_uas; - void showNullMAVErrorMessageBox(); - void initConnections(); -signals: - -public slots: - virtual void activeUASSet(UASInterface *uas); - virtual void parameterChanged(int uas, int component, QString parameterName, QVariant value); -}; - -#endif // AP2CONFIGWIDGET_H diff --git a/src/ui/configuration/AccelCalibrationConfig.cc b/src/ui/configuration/AccelCalibrationConfig.cc deleted file mode 100644 index 8be7913521a392640284544994dcd634343ee9f5..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AccelCalibrationConfig.cc +++ /dev/null @@ -1,132 +0,0 @@ -#include "AccelCalibrationConfig.h" - - -AccelCalibrationConfig::AccelCalibrationConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - connect(ui.calibrateAccelButton,SIGNAL(clicked()),this,SLOT(calibrateButtonClicked())); - - m_accelAckCount=0; - initConnections(); -} - -AccelCalibrationConfig::~AccelCalibrationConfig() -{ -} -void AccelCalibrationConfig::activeUASSet(UASInterface *uas) -{ - if (m_uas) - { - disconnect(m_uas,SIGNAL(textMessageReceived(int,int,int,QString)),this,SLOT(uasTextMessageReceived(int,int,int,QString))); - } - AP2ConfigWidget::activeUASSet(uas); - if (!uas) - { - return; - } - connect(m_uas,SIGNAL(textMessageReceived(int,int,int,QString)),this,SLOT(uasTextMessageReceived(int,int,int,QString))); - -} - -void AccelCalibrationConfig::calibrateButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (m_accelAckCount == 0) - { - MAV_CMD command = MAV_CMD_PREFLIGHT_CALIBRATION; - int confirm = 0; - float param1 = 0.0; - float param2 = 0.0; - float param3 = 0.0; - float param4 = 0.0; - float param5 = 1.0; - float param6 = 0.0; - float param7 = 0.0; - int component = 1; - m_uas->executeCommand(command, confirm, param1, param2, param3, param4, param5, param6, param7, component); - } - else if (m_accelAckCount <= 5) - { - m_uas->executeCommandAck(m_accelAckCount++,true); - } - else - { - m_uas->executeCommandAck(m_accelAckCount++,true); - ui.calibrateAccelButton->setText("Calibrate\nAccelerometer"); - if (m_accelAckCount > 8) - { - //We've clicked too many times! Reset. - for (int i=0;i<8;i++) - { - m_uas->executeCommandAck(i,true); - } - m_accelAckCount = 0; - } - } - -} -void AccelCalibrationConfig::hideEvent(QHideEvent *evt) -{ - Q_UNUSED(evt); - - if (!m_uas || !m_accelAckCount) - { - return; - } - for (int i=m_accelAckCount;i<8;i++) - { - m_uas->executeCommandAck(i,true); //Clear out extra commands. - } -} -void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid, int severity, QString text) -{ - Q_UNUSED(uasid); - Q_UNUSED(componentid); - - //command received: " Severity 1 - //Place APM Level and press any key" severity 5 - if (severity == 5) - { - //This is a calibration instruction - if (m_accelAckCount == 0) - { - //Calibration Sucessful\r" - ui.calibrateAccelButton->setText("Continue"); - m_accelAckCount++; - } - if (m_accelAckCount == 7) - { - //All finished - //ui.outputLabel->setText(ui.outputLabel->text() + "\n" + text); - ui.outputLabel->setText(text); - m_accelAckCount++; - } - if (m_accelAckCount == 8) - { - if (text.contains("Calibration") && text.contains("successful")) - { - m_accelAckCount = 0; - } - else if (text.contains("Calibration") && text.contains("FAILED")) //Failure - { - m_accelAckCount = 0; - } - ui.outputLabel->setText(ui.outputLabel->text() + "\n" + text); - } - else - { - ui.outputLabel->setText(text.replace("press any key","click Continue below")); - if (!this->isVisible()) - { - //Clear out! - m_uas->executeCommandAck(m_accelAckCount++,true); - ui.calibrateAccelButton->setText("Calibrate\nAccelerometer"); - } - } - } - -} diff --git a/src/ui/configuration/AccelCalibrationConfig.h b/src/ui/configuration/AccelCalibrationConfig.h deleted file mode 100644 index 152656253405c78df81c81b3a68a93f65fa86683..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AccelCalibrationConfig.h +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef ACCELCALIBRATIONCONFIG_H -#define ACCELCALIBRATIONCONFIG_H - -#include -#include "ui_AccelCalibrationConfig.h" -#include "UASManager.h" -#include "UASInterface.h" -#include "AP2ConfigWidget.h" - -class AccelCalibrationConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit AccelCalibrationConfig(QWidget *parent = 0); - ~AccelCalibrationConfig(); -protected: - void hideEvent(QHideEvent *evt); -private slots: - void activeUASSet(UASInterface *uas); - void calibrateButtonClicked(); - void uasTextMessageReceived(int uasid, int componentid, int severity, QString text); -private: - int m_accelAckCount; - Ui::AccelCalibrationConfig ui; -}; - -#endif // ACCELCALIBRATIONCONFIG_H diff --git a/src/ui/configuration/AccelCalibrationConfig.ui b/src/ui/configuration/AccelCalibrationConfig.ui deleted file mode 100644 index 6555a572584b14a77a048a68d7d8cb0a2ccd2c13..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AccelCalibrationConfig.ui +++ /dev/null @@ -1,62 +0,0 @@ - - - AccelCalibrationConfig - - - - 0 - 0 - 576 - 354 - - - - Form - - - - - 10 - 0 - 231 - 31 - - - - <h2>Accelerometer Calibration</h2> - - - false - - - - - - 70 - 160 - 111 - 41 - - - - Calibrate -Accelerometer - - - - - - 20 - 50 - 311 - 101 - - - - - - - - - - diff --git a/src/ui/configuration/AdvParameterList.cc b/src/ui/configuration/AdvParameterList.cc deleted file mode 100644 index bc0bb670234ffa0e1e78a036697276a75c47c2fb..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AdvParameterList.cc +++ /dev/null @@ -1,55 +0,0 @@ -#include "AdvParameterList.h" - - -AdvParameterList::AdvParameterList(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - ui.tableWidget->setColumnCount(4); - ui.tableWidget->horizontalHeader()->hide(); - ui.tableWidget->verticalHeader()->hide(); - ui.tableWidget->setColumnWidth(0,200); - ui.tableWidget->setColumnWidth(1,100); - ui.tableWidget->setColumnWidth(2,200); - ui.tableWidget->setColumnWidth(3,800); - initConnections(); -} - -AdvParameterList::~AdvParameterList() -{ -} -void AdvParameterList::setParameterMetaData(QString name,QString humanname,QString description) -{ - m_paramToNameMap[name] = humanname; - m_paramToDescriptionMap[name] = description; -} - -void AdvParameterList::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (!m_paramValueMap.contains(parameterName)) - { - ui.tableWidget->setRowCount(ui.tableWidget->rowCount()+1); - if (m_paramToNameMap.contains(parameterName)) - { - ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,0,new QTableWidgetItem(m_paramToNameMap[parameterName])); - } - else - { - ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,0,new QTableWidgetItem("Unknown")); - } - ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,1,new QTableWidgetItem(QString::number(value.toFloat(),'f',2))); - ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,2,new QTableWidgetItem(parameterName)); - if (m_paramToDescriptionMap.contains(parameterName)) - { - ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem(m_paramToDescriptionMap[parameterName])); - } - else - { - ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem("Unknown")); - } - m_paramValueMap[parameterName] = ui.tableWidget->item(ui.tableWidget->rowCount()-1,1); - } - m_paramValueMap[parameterName]->setText(QString::number(value.toFloat(),'f',2)); -} diff --git a/src/ui/configuration/AdvParameterList.h b/src/ui/configuration/AdvParameterList.h deleted file mode 100644 index 6ff55a22ff28b105f82f780436805539a88d3628..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AdvParameterList.h +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef ADVPARAMETERLIST_H -#define ADVPARAMETERLIST_H - -#include -#include "ui_AdvParameterList.h" -#include "AP2ConfigWidget.h" - -class AdvParameterList : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit AdvParameterList(QWidget *parent = 0); - void setParameterMetaData(QString name,QString humanname,QString description); - ~AdvParameterList(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); -private: - QMap m_paramValueMap; - QMap m_paramToNameMap; - QMap m_paramToDescriptionMap; - Ui::AdvParameterList ui; -}; - -#endif // ADVPARAMETERLIST_H diff --git a/src/ui/configuration/AdvParameterList.ui b/src/ui/configuration/AdvParameterList.ui deleted file mode 100644 index 3b18893d2779326a068dca7fbd15ced27f7f1b0a..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AdvParameterList.ui +++ /dev/null @@ -1,31 +0,0 @@ - - - AdvParameterList - - - - 0 - 0 - 666 - 497 - - - - Form - - - - - - <h2>Full Parameter List</h2> - - - - - - - - - - - diff --git a/src/ui/configuration/AdvancedParamConfig.cc b/src/ui/configuration/AdvancedParamConfig.cc deleted file mode 100644 index 8edbe1fd64eff09d572d9bc31a3ee74f45d583b5..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AdvancedParamConfig.cc +++ /dev/null @@ -1,67 +0,0 @@ -#include "AdvancedParamConfig.h" - - -AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - initConnections(); -} - -AdvancedParamConfig::~AdvancedParamConfig() -{ -} -void AdvancedParamConfig::addRange(QString title,QString description,QString param,double min,double max) -{ - ParamWidget *widget = new ParamWidget(param,ui.scrollAreaWidgetContents); - connect(widget,SIGNAL(doubleValueChanged(QString,double)),this,SLOT(doubleValueChanged(QString,double))); - connect(widget,SIGNAL(intValueChanged(QString,int)),this,SLOT(intValueChanged(QString,int))); - m_paramToWidgetMap[param] = widget; - widget->setupDouble(title + "(" + param + ")",description,0,min,max); - ui.verticalLayout->addWidget(widget); - widget->show(); -} - -void AdvancedParamConfig::addCombo(QString title,QString description,QString param,QList > valuelist) -{ - ParamWidget *widget = new ParamWidget(param,ui.scrollAreaWidgetContents); - connect(widget,SIGNAL(doubleValueChanged(QString,double)),this,SLOT(doubleValueChanged(QString,double))); - connect(widget,SIGNAL(intValueChanged(QString,int)),this,SLOT(intValueChanged(QString,int))); - m_paramToWidgetMap[param] = widget; - widget->setupCombo(title + "(" + param + ")",description,valuelist); - ui.verticalLayout->addWidget(widget); - widget->show(); -} -void AdvancedParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (m_paramToWidgetMap.contains(parameterName)) - { - if (value.type() == QVariant::Double) - { - m_paramToWidgetMap[parameterName]->setValue(value.toDouble()); - } - else - { - m_paramToWidgetMap[parameterName]->setValue(value.toInt()); - } - } -} -void AdvancedParamConfig::doubleValueChanged(QString param,double value) -{ - if (!m_uas) - { - this->showNullMAVErrorMessageBox(); - } - m_uas->getParamManager()->setParameter(1,param,value); -} - -void AdvancedParamConfig::intValueChanged(QString param,int value) -{ - if (!m_uas) - { - this->showNullMAVErrorMessageBox(); - } - m_uas->getParamManager()->setParameter(1,param,value); -} diff --git a/src/ui/configuration/AdvancedParamConfig.h b/src/ui/configuration/AdvancedParamConfig.h deleted file mode 100644 index 07e55d61d1d697e360861cc9814afaada7f2bdb1..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AdvancedParamConfig.h +++ /dev/null @@ -1,26 +0,0 @@ -#ifndef ADVANCEDPARAMCONFIG_H -#define ADVANCEDPARAMCONFIG_H - -#include -#include "ui_AdvancedParamConfig.h" -#include "AP2ConfigWidget.h" -#include "ParamWidget.h" -class AdvancedParamConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit AdvancedParamConfig(QWidget *parent = 0); - ~AdvancedParamConfig(); - void addRange(QString title,QString description,QString param,double min,double max); - void addCombo(QString title,QString description,QString param,QList > valuelist); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void doubleValueChanged(QString param,double value); - void intValueChanged(QString param,int value); -private: - QMap m_paramToWidgetMap; - Ui::AdvancedParamConfig ui; -}; - -#endif // ADVANCEDPARAMCONFIG_H diff --git a/src/ui/configuration/AdvancedParamConfig.ui b/src/ui/configuration/AdvancedParamConfig.ui deleted file mode 100644 index 596861a3a2aeb2ea2792cc74ea184cf89ee3dae1..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AdvancedParamConfig.ui +++ /dev/null @@ -1,50 +0,0 @@ - - - AdvancedParamConfig - - - - 0 - 0 - 725 - 632 - - - - Form - - - - - - <h2>Advanced Params</h2> - - - - - - - true - - - - - 0 - 0 - 705 - 585 - - - - - - - - - - - - - - - diff --git a/src/ui/configuration/AirspeedConfig.cc b/src/ui/configuration/AirspeedConfig.cc deleted file mode 100644 index 25da75fc28042d4b54529d786e2dcc5ebeb8b8be..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AirspeedConfig.cc +++ /dev/null @@ -1,86 +0,0 @@ -#include "AirspeedConfig.h" -#include - -AirspeedConfig::AirspeedConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(enableCheckBoxClicked(bool))); - connect(ui.useAirspeedCheckBox,SIGNAL(toggled(bool)),this,SLOT(useCheckBoxClicked(bool))); - initConnections(); -} - -AirspeedConfig::~AirspeedConfig() -{ -} -void AirspeedConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "ARSPD_ENABLE") - { - if (value.toInt() == 0) - { - disconnect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(enableCheckBoxClicked(bool))); - ui.enableCheckBox->setChecked(false); - connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(enableCheckBoxClicked(bool))); - ui.useAirspeedCheckBox->setEnabled(false); - } - else - { - disconnect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(enableCheckBoxClicked(bool))); - ui.enableCheckBox->setChecked(true); - connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(enableCheckBoxClicked(bool))); - ui.useAirspeedCheckBox->setEnabled(true); - } - } - else if (parameterName == "ARSPD_USE") - { - if (value.toInt() == 0) - { - disconnect(ui.useAirspeedCheckBox,SIGNAL(toggled(bool)),this,SLOT(useCheckBoxClicked(bool))); - ui.useAirspeedCheckBox->setChecked(false); - connect(ui.useAirspeedCheckBox,SIGNAL(toggled(bool)),this,SLOT(useCheckBoxClicked(bool))); - } - else - { - disconnect(ui.useAirspeedCheckBox,SIGNAL(toggled(bool)),this,SLOT(useCheckBoxClicked(bool))); - ui.useAirspeedCheckBox->setChecked(true); - connect(ui.useAirspeedCheckBox,SIGNAL(toggled(bool)),this,SLOT(useCheckBoxClicked(bool))); - } - } -} - -void AirspeedConfig::useCheckBoxClicked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->getParamManager()->setParameter(1,"ARSPD_USE",1); - } - else - { - m_uas->getParamManager()->setParameter(1,"ARSPD_USE",0); - } -} - -void AirspeedConfig::enableCheckBoxClicked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->getParamManager()->setParameter(1,"ARSPD_ENABLE",1); - } - else - { - m_uas->getParamManager()->setParameter(1,"ARSPD_ENABLE",0); - } -} diff --git a/src/ui/configuration/AirspeedConfig.h b/src/ui/configuration/AirspeedConfig.h deleted file mode 100644 index 1646b36759fa0154eb23120203edc0873ead70bc..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AirspeedConfig.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef AIRSPEEDCONFIG_H -#define AIRSPEEDCONFIG_H - -#include -#include "AP2ConfigWidget.h" -#include "ui_AirspeedConfig.h" - -class AirspeedConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit AirspeedConfig(QWidget *parent = 0); - ~AirspeedConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void useCheckBoxClicked(bool checked); - void enableCheckBoxClicked(bool checked); -private: - Ui::AirspeedConfig ui; -}; - -#endif // AIRSPEEDCONFIG_H diff --git a/src/ui/configuration/AirspeedConfig.ui b/src/ui/configuration/AirspeedConfig.ui deleted file mode 100644 index 7d33cae3664b7dec1d1e5ce1bbf64beca2735ed7..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AirspeedConfig.ui +++ /dev/null @@ -1,82 +0,0 @@ - - - AirspeedConfig - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - 20 - 20 - 131 - 31 - - - - <h2>Airspeed</h2> - - - false - - - - - - 20 - 60 - 71 - 71 - - - - - - - :/files/images/devices/BR-0004-03-2.jpg - - - true - - - - - - 110 - 70 - 70 - 17 - - - - Enable - - - - - - 110 - 100 - 91 - 17 - - - - Use Airspeed - - - - - - - - diff --git a/src/ui/configuration/AntennaTrackerConfig.cc b/src/ui/configuration/AntennaTrackerConfig.cc deleted file mode 100644 index 6b406da474fe3a268c47a42eee4255ca83f4c037..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AntennaTrackerConfig.cc +++ /dev/null @@ -1,11 +0,0 @@ -#include "AntennaTrackerConfig.h" - - -AntennaTrackerConfig::AntennaTrackerConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); -} - -AntennaTrackerConfig::~AntennaTrackerConfig() -{ -} diff --git a/src/ui/configuration/AntennaTrackerConfig.h b/src/ui/configuration/AntennaTrackerConfig.h deleted file mode 100644 index 35271cb288b08e58252f7599c6f65cee07062017..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AntennaTrackerConfig.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef ANTENNATRACKERCONFIG_H -#define ANTENNATRACKERCONFIG_H - -#include -#include "ui_AntennaTrackerConfig.h" - -class AntennaTrackerConfig : public QWidget -{ - Q_OBJECT - -public: - explicit AntennaTrackerConfig(QWidget *parent = 0); - ~AntennaTrackerConfig(); - -private: - Ui::AntennaTrackerConfig ui; -}; - -#endif // ANTENNATRACKERCONFIG_H diff --git a/src/ui/configuration/AntennaTrackerConfig.ui b/src/ui/configuration/AntennaTrackerConfig.ui deleted file mode 100644 index f355fc4ca95baf26f51d6789540354c27152e04d..0000000000000000000000000000000000000000 --- a/src/ui/configuration/AntennaTrackerConfig.ui +++ /dev/null @@ -1,311 +0,0 @@ - - - AntennaTrackerConfig - - - - 0 - 0 - 1171 - 560 - - - - Form - - - - - 20 - 10 - 151 - 31 - - - - <h2>Antenna Tracker</h2> - - - false - - - - - - 20 - 50 - 46 - 13 - - - - Interface - - - - - - 80 - 50 - 69 - 22 - - - - - - - 160 - 50 - 69 - 22 - - - - - - - 240 - 50 - 69 - 22 - - - - - - - 320 - 50 - 75 - 23 - - - - Connect - - - - - - 20 - 80 - 581 - 131 - - - - Pan - - - - - - - - - - Angle - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - PWM - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Center PWM - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - - - - - - - - - - - - Trim - - - Qt::AlignCenter - - - - - - - -180 - - - 0 - - - Qt::Horizontal - - - - - - - 0 - - - Qt::AlignCenter - - - - - - - - - Rev - - - - - - - - - - - 20 - 220 - 581 - 131 - - - - Tilt - - - - - - - - - - Angle - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - PWM - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Center PWM - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - - - - - - - - - - - - Trim - - - Qt::AlignCenter - - - - - - - -180 - - - 180 - - - Qt::Horizontal - - - - - - - 0 - - - Qt::AlignCenter - - - - - - - - - Rev - - - - - - - - - - - diff --git a/src/ui/configuration/ApmFirmwareConfig.cc b/src/ui/configuration/ApmFirmwareConfig.cc deleted file mode 100644 index 47e1ac72e9d84d1e0402d7d9deac5a4e8f640364..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmFirmwareConfig.cc +++ /dev/null @@ -1,462 +0,0 @@ -#include - -#include "LinkManager.h" -#include "LinkInterface.h" -#include -#include -#include "SerialLink.h" - -#include "ApmFirmwareConfig.h" - -ApmFirmwareConfig::ApmFirmwareConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); - //firmwareStatus = 0; - m_betaFirmwareChecked = false; - m_tempFirmwareFile=0; - // - - //QNetworkRequest req(QUrl("https://raw.github.com/diydrones/binary/master/Firmware/firmware2.xml")); - - - - m_networkManager = new QNetworkAccessManager(this); - - connect(ui.roverPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.planePushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.copterPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.hexaPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.octaQuadPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.octaPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.quadPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.triPushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - connect(ui.y6PushButton,SIGNAL(clicked()),this,SLOT(flashButtonClicked())); - QTimer::singleShot(10000,this,SLOT(requestFirmwares())); - connect(ui.betaFirmwareButton,SIGNAL(clicked(bool)),this,SLOT(betaFirmwareButtonClicked(bool))); - - ui.progressBar->setMaximum(100); - ui.progressBar->setValue(0); - - ui.textBrowser->setVisible(false); - connect(ui.showOutputCheckBox,SIGNAL(clicked(bool)),ui.textBrowser,SLOT(setVisible(bool))); - - /*addBetaLabel(ui.roverPushButton); - addBetaLabel(ui.planePushButton); - addBetaLabel(ui.copterPushButton); - addBetaLabel(ui.quadPushButton); - addBetaLabel(ui.hexaPushButton); - addBetaLabel(ui.octaQuadPushButton); - addBetaLabel(ui.octaPushButton); - addBetaLabel(ui.triPushButton); - addBetaLabel(ui.y6PushButton);*/ - -} -void ApmFirmwareConfig::hideBetaLabels() -{ - for (int i=0;ihide(); - } - ui.warningLabel->hide(); -} - -void ApmFirmwareConfig::showBetaLabels() -{ - for (int i=0;ishow(); - } - ui.warningLabel->show(); -} - -void ApmFirmwareConfig::addBetaLabel(QWidget *parent) -{ - QLabel *label = new QLabel(parent); - QVBoxLayout *layout = new QVBoxLayout(); - parent->setLayout(layout); - label->setAlignment(Qt::AlignRight | Qt::AlignBottom); - label->setText("

BETA

"); - layout->addWidget(label); - m_betaButtonLabelList.append(label); -} - -void ApmFirmwareConfig::requestBetaFirmwares() -{ - m_betaFirmwareChecked = true; - showBetaLabels(); - QNetworkReply *reply1 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-heli/git-version.txt"))); - QNetworkReply *reply2 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-quad/git-version.txt"))); - QNetworkReply *reply3 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-hexa/git-version.txt"))); - QNetworkReply *reply4 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-octa/git-version.txt"))); - QNetworkReply *reply5 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-octa-quad/git-version.txt"))); - QNetworkReply *reply6 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-tri/git-version.txt"))); - QNetworkReply *reply7 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/beta/apm2-y6/git-version.txt"))); - QNetworkReply *reply8 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Plane/beta/apm2/git-version.txt"))); - QNetworkReply *reply9 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Rover/beta/apm2/git-version.txt"))); - - m_buttonToUrlMap[ui.roverPushButton] = "http://firmware.diydrones.com/Rover/beta/apm2/APMrover2.hex"; - m_buttonToUrlMap[ui.planePushButton] = "http://firmware.diydrones.com/Plane/beta/apm2/ArduPlane.hex"; - m_buttonToUrlMap[ui.copterPushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-heli/ArduCopter.hex"; - m_buttonToUrlMap[ui.hexaPushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-hexa/ArduCopter.hex"; - m_buttonToUrlMap[ui.octaQuadPushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-octa-quad/ArduCopter.hex"; - m_buttonToUrlMap[ui.octaPushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-octa/ArduCopter.hex"; - m_buttonToUrlMap[ui.quadPushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-quad/ArduCopter.hex"; - m_buttonToUrlMap[ui.triPushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-tri/ArduCopter.hex"; - m_buttonToUrlMap[ui.y6PushButton] = "http://firmware.diydrones.com/Copter/beta/apm2-y6/ArduCopter.hex"; - - //http://firmware.diydrones.com/Plane/stable/apm2/ArduPlane.hex - connect(reply1,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply1,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply2,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply2,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply3,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply3,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply4,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply4,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply5,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply5,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply6,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply6,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply7,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply7,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply8,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply8,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply9,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply9,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - qDebug() << "Getting Beta firmware..."; -} - -void ApmFirmwareConfig::requestFirmwares() -{ - m_betaFirmwareChecked = false; - hideBetaLabels(); - QNetworkReply *reply1 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-heli/git-version.txt"))); - QNetworkReply *reply2 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-quad/git-version.txt"))); - QNetworkReply *reply3 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-hexa/git-version.txt"))); - QNetworkReply *reply4 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-octa/git-version.txt"))); - QNetworkReply *reply5 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-octa-quad/git-version.txt"))); - QNetworkReply *reply6 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-tri/git-version.txt"))); - QNetworkReply *reply7 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Copter/stable/apm2-y6/git-version.txt"))); - QNetworkReply *reply8 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Plane/stable/apm2/git-version.txt"))); - QNetworkReply *reply9 = m_networkManager->get(QNetworkRequest(QUrl("http://firmware.diydrones.com/Rover/stable/apm2/git-version.txt"))); - - m_buttonToUrlMap[ui.roverPushButton] = "http://firmware.diydrones.com/Rover/stable/apm2/APMrover2.hex"; - m_buttonToUrlMap[ui.planePushButton] = "http://firmware.diydrones.com/Plane/stable/apm2/ArduPlane.hex"; - m_buttonToUrlMap[ui.copterPushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-heli/ArduCopter.hex"; - m_buttonToUrlMap[ui.hexaPushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-hexa/ArduCopter.hex"; - m_buttonToUrlMap[ui.octaQuadPushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-octa-quad/ArduCopter.hex"; - m_buttonToUrlMap[ui.octaPushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-octa/ArduCopter.hex"; - m_buttonToUrlMap[ui.quadPushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-quad/ArduCopter.hex"; - m_buttonToUrlMap[ui.triPushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-tri/ArduCopter.hex"; - m_buttonToUrlMap[ui.y6PushButton] = "http://firmware.diydrones.com/Copter/stable/apm2-y6/ArduCopter.hex"; - - //http://firmware.diydrones.com/Plane/stable/apm2/ArduPlane.hex - connect(reply1,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply1,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply2,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply2,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply3,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply3,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply4,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply4,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply5,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply5,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply6,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply6,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply7,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply7,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply8,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply8,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply9,SIGNAL(finished()),this,SLOT(firmwareListFinished())); - connect(reply9,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - qDebug() << "Getting Stable firmware..."; -} - -void ApmFirmwareConfig::betaFirmwareButtonClicked(bool betafirmwareenabled) -{ - if (betafirmwareenabled) - { - ui.label->setText(tr("

Beta Firmware

")); - ui.betaFirmwareButton->setText(tr("Stable Firmware")); - requestBetaFirmwares(); - } - else - { - ui.label->setText(tr("

Firmware

")); - ui.betaFirmwareButton->setText(tr("Beta Firmware")); - requestFirmwares(); - } -} -void ApmFirmwareConfig::firmwareProcessFinished(int status) -{ - QProcess *proc = qobject_cast(sender()); - if (!proc) - { - return; - } - if (status != 0) - { - //Error of some kind - QMessageBox::information(0,tr("Error"),tr("An error has occured during the upload process. See window for details")); - ui.textBrowser->setVisible(true); - ui.showOutputCheckBox->setChecked(true); - ui.textBrowser->setPlainText(ui.textBrowser->toPlainText().append("\n\nERROR!!\n" + proc->errorString())); - QScrollBar *sb = ui.textBrowser->verticalScrollBar(); - if (sb) - { - sb->setValue(sb->maximum()); - } - ui.statusLabel->setText(tr("Error during upload")); - } - else - { - //Ensure we're reading 100% - ui.progressBar->setValue(100); - ui.statusLabel->setText(tr("Upload complete")); - } - //qDebug() << "Upload finished!" << QString::number(status); - m_tempFirmwareFile->deleteLater(); //This will remove the temporary file. - m_tempFirmwareFile = 0; - -} -void ApmFirmwareConfig::firmwareProcessReadyRead() -{ - QProcess *proc = qobject_cast(sender()); - if (!proc) - { - return; - } - QString output = proc->readAllStandardError() + proc->readAllStandardOutput(); - if (output.contains("Writing")) - { - //firmwareStatus->resetProgress(); - ui.progressBar->setValue(0); - } - else if (output.contains("Reading")) - { - ui.progressBar->setValue(50); - } - if (output.startsWith("#")) - { - ui.progressBar->setValue(ui.progressBar->value()+1); - - ui.textBrowser->setPlainText(ui.textBrowser->toPlainText().append(output)); - QScrollBar *sb = ui.textBrowser->verticalScrollBar(); - if (sb) - { - sb->setValue(sb->maximum()); - } - } - else - { - ui.textBrowser->setPlainText(ui.textBrowser->toPlainText().append(output + "\n")); - QScrollBar *sb = ui.textBrowser->verticalScrollBar(); - if (sb) - { - sb->setValue(sb->maximum()); - } - } - - qDebug() << "E:" << output; - //qDebug() << "AVR Output:" << proc->readAllStandardOutput(); - //qDebug() << "AVR Output:" << proc->readAllStandardError(); -} - -void ApmFirmwareConfig::downloadFinished() -{ - qDebug() << "Download finished, flashing firmware"; - QNetworkReply *reply = qobject_cast(sender()); - if (!reply) - { - return; - } - QByteArray hex = reply->readAll(); - m_tempFirmwareFile = new QTemporaryFile(); - m_tempFirmwareFile->open(); - m_tempFirmwareFile->write(hex); - m_tempFirmwareFile->flush(); - m_tempFirmwareFile->close(); - //tempfirmware.fileName() - QProcess *process = new QProcess(this); - connect(process,SIGNAL(finished(int)),this,SLOT(firmwareProcessFinished(int))); - connect(process,SIGNAL(readyReadStandardOutput()),this,SLOT(firmwareProcessReadyRead())); - connect(process,SIGNAL(readyReadStandardError()),this,SLOT(firmwareProcessReadyRead())); - connect(process,SIGNAL(error(QProcess::ProcessError)),this,SLOT(firmwareProcessError(QProcess::ProcessError))); - QList portList = QSerialPortInfo::availablePorts(); - - - foreach (const QSerialPortInfo &info, portList) - { - qDebug() << "PortName : " << info.portName() - << "Description : " << info.description(); - qDebug() << "Manufacturer: " << info.manufacturer(); - - - } - - //info.manufacturer() == "Arduino LLC (www.arduino.cc)" - //info.description() == "%mega2560.name%" - - qDebug() << "Attempting to reset port"; - - QSerialPort port; - - port.setPortName(m_detectedComPort); - port.open(QIODevice::ReadWrite); - port.setDataTerminalReady(true); - port.waitForBytesWritten(250); - port.setDataTerminalReady(false); - port.close(); - - QString avrdudeExecutable; - QStringList stringList; - - ui.statusLabel->setText(tr("Flashing")); -#ifdef Q_OS_WIN - stringList = QStringList() << "-Cavrdude/avrdude.conf" << "-pm2560" - << "-cstk500" << QString("-P").append(m_detectedComPort) - << QString("-Uflash:w:").append(m_tempFirmwareFile->fileName()).append(":i"); - - avrdudeExecutable = "avrdude/avrdude.exe"; -#endif -#ifdef Q_OS_MAC - stringList = QStringList() << "-v" << "-pm2560" - << "-cstk500" << QString("-P/dev/cu.").append(m_detectedComPort) - << QString("-Uflash:w:").append(m_tempFirmwareFile->fileName()).append(":i"); - avrdudeExecutable = "/usr/local/CrossPack-AVR/bin/avrdude"; -#endif - - // Start the Flashing - qDebug() << avrdudeExecutable << stringList; - process->start(avrdudeExecutable,stringList); -} -void ApmFirmwareConfig::firmwareProcessError(QProcess::ProcessError error) -{ - qDebug() << "Error:" << error; -} -void ApmFirmwareConfig::firmwareDownloadProgress(qint64 received,qint64 total) -{ - ui.progressBar->setValue( 100.0 * ((double)received/(double)total)); -} - -void ApmFirmwareConfig::flashButtonClicked() -{ - QPushButton *senderbtn = qobject_cast(sender()); - if (m_buttonToUrlMap.contains(senderbtn)) - { - bool foundconnected = false; - for (int i=0;igetLinks().size();i++) - { - if (LinkManager::instance()->getLinks()[i]->isConnected()) - { - //This is likely the serial link we want. - SerialLink *link = qobject_cast(LinkManager::instance()->getLinks()[i]); - if (!link) - { - qDebug() << "Eror, trying to program over a non serial link. This should not happen"; - return; - } - if (!(QMessageBox::question(this,tr("WARNING"),tr("You are about to upload new firmware to your board. This will disconnect you if you are currently connected. Be sure the MAV is on the ground, and connected over USB/Serial link.\n\nDo you wish to proceed?"),QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes)) - { - return; - } - - m_detectedComPort = link->getPortName(); - link->requestReset(); - foundconnected = true; - link->disconnect(); - link->wait(1000); // Wait 1 second for it to disconnect. - } - } - if (!foundconnected) - { - QMessageBox::information(0,tr("Error"),tr("You must be connected to a MAV over serial link to flash firmware. Please connect to a MAV then try again")); - return; - } - - qDebug() << "Go download:" << m_buttonToUrlMap[senderbtn]; - QNetworkReply *reply = m_networkManager->get(QNetworkRequest(QUrl(m_buttonToUrlMap[senderbtn]))); - //http://firmware.diydrones.com/Plane/stable/apm2/ArduPlane.hex - connect(reply,SIGNAL(finished()),this,SLOT(downloadFinished())); - - connect(reply,SIGNAL(error(QNetworkReply::NetworkError)),this,SLOT(firmwareListError(QNetworkReply::NetworkError))); - connect(reply,SIGNAL(downloadProgress(qint64,qint64)),this,SLOT(firmwareDownloadProgress(qint64,qint64))); - ui.statusLabel->setText("Downloading"); - } -} - -void ApmFirmwareConfig::firmwareListError(QNetworkReply::NetworkError error) -{ - Q_UNUSED(error); - QNetworkReply *reply = qobject_cast(sender()); - qDebug() << "Error!" << reply->errorString(); -} -bool ApmFirmwareConfig::stripVersionFromGitReply(QString url, QString reply,QString type,QString stable,QString *out) -{ - if (url.contains(type) && url.contains("git-version.txt") && url.contains(stable)) - { - QString version = reply.mid(reply.indexOf("APMVERSION:")+12).replace("\n","").replace("\r","").trimmed(); - *out = version; - return true; - } - return false; - -} - -void ApmFirmwareConfig::firmwareListFinished() -{ - QNetworkReply *reply = qobject_cast(sender()); - QString replystr = reply->readAll(); - QString outstr = ""; - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-heli",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.copterLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-quad",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.quadLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-hexa",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.hexaLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-octa-quad",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.octaQuadLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-octa",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.octaLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-tri",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.triLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"apm2-y6",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.y6Label->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"Plane",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.planeLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - if (stripVersionFromGitReply(reply->url().toString(),replystr,"Rover",(m_betaFirmwareChecked ? "beta" : "stable"),&outstr)) - { - ui.roverLabel->setText((m_betaFirmwareChecked ? "BETA " : "") + outstr); - return; - } - //qDebug() << "Match not found for:" << reply->url(); - //qDebug() << "Git version line:" << replystr; -} - -ApmFirmwareConfig::~ApmFirmwareConfig() -{ -} diff --git a/src/ui/configuration/ApmFirmwareConfig.h b/src/ui/configuration/ApmFirmwareConfig.h deleted file mode 100644 index 37e7bf40f2cd781ebb50c26999fa175b9dfd5f3c..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmFirmwareConfig.h +++ /dev/null @@ -1,66 +0,0 @@ -#ifndef APMFIRMWARECONFIG_H -#define APMFIRMWARECONFIG_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "ui_ApmFirmwareConfig.h" - -class ApmFirmwareConfig : public QWidget -{ - Q_OBJECT - -public: - explicit ApmFirmwareConfig(QWidget *parent = 0); - ~ApmFirmwareConfig(); -private slots: - void firmwareListFinished(); - void firmwareListError(QNetworkReply::NetworkError error); - void flashButtonClicked(); - void betaFirmwareButtonClicked(bool betafirmwareenabled); - void downloadFinished(); - void firmwareProcessFinished(int status); - void firmwareProcessReadyRead(); - void firmwareProcessError(QProcess::ProcessError error); - void firmwareDownloadProgress(qint64 received,qint64 total); - void requestFirmwares(); - void requestBetaFirmwares(); -private: - void addBetaLabel(QWidget *parent); - void hideBetaLabels(); - void showBetaLabels(); - //ApmFirmwareStatus *firmwareStatus; - QString m_detectedComPort; - QTemporaryFile *m_tempFirmwareFile; - QNetworkAccessManager *m_networkManager; - QList m_betaButtonLabelList; - bool stripVersionFromGitReply(QString url,QString reply,QString type,QString stable,QString *out); - bool m_betaFirmwareChecked; - QMap m_buttonToUrlMap; - Ui::ApmFirmwareConfig ui; - class FirmwareDef - { - public: - QString url; - QString url2560; - QString url25602; - QString urlpx4; - QString type; - QString name; - QString desc; - int version; - }; - QList m_firmwareList; -}; - -#endif // APMFIRMWARECONFIG_H diff --git a/src/ui/configuration/ApmFirmwareConfig.ui b/src/ui/configuration/ApmFirmwareConfig.ui deleted file mode 100644 index 4350d71e9c8ce8ccb33617e9695548f1125666a8..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmFirmwareConfig.ui +++ /dev/null @@ -1,514 +0,0 @@ - - - ApmFirmwareConfig - - - - 0 - 0 - 868 - 684 - - - - Form - - - - - 10 - 20 - 211 - 31 - - - - <h2>Firmware</h2> - - - - - - 30 - 60 - 801 - 371 - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/heli.png:/files/images/firmware/heli.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/quadplus.png:/files/images/firmware/quadplus.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/plane.png:/files/images/firmware/plane.png - - - - 150 - 150 - - - - - - - - ArduPlane vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/triy.png:/files/images/firmware/triy.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/hexay.png:/files/images/firmware/hexay.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/rover.png:/files/images/firmware/rover.png - - - - 150 - 150 - - - - - - - - ArduRover vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/octaplus.png:/files/images/firmware/octaplus.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/octx.png:/files/images/firmware/octx.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - - 150 - 150 - - - - - 150 - 150 - - - - - - - - :/files/images/firmware/hexaplus.png:/files/images/firmware/hexaplus.png - - - - 150 - 150 - - - - - - - - ArduCopter vX.XX - - - Qt::AlignCenter - - - - - - - - - - - 700 - 440 - 131 - 23 - - - - Beta firmware - - - true - - - false - - - - - - 30 - 490 - 801 - 23 - - - - 24 - - - - - - 30 - 520 - 801 - 151 - - - - - - - 710 - 470 - 101 - 17 - - - - Show Output - - - - - - 30 - 440 - 141 - 21 - - - - Status - - - - - - 180 - 440 - 491 - 16 - - - - <html><head/><body><p><span style=" font-size:large; font-weight:600; color:#e90000;">WARNING:</span><span style=" font-size:large; font-weight:600; color:#ffaa00;"> Only install BETA firmware if you are an experienced tester.</span></p></body></html> - - - - - - - - diff --git a/src/ui/configuration/ApmHardwareConfig.cc b/src/ui/configuration/ApmHardwareConfig.cc deleted file mode 100644 index 38aef8b6a7f8c0800e2f3145d604db94cb5b0ff3..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmHardwareConfig.cc +++ /dev/null @@ -1,187 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2013 Michael Carpenter (malcom2073@gmail.com) - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief APM Hardware Configuration widget source. - * - * @author Michael Carpenter - * - */ -#include "ApmHardwareConfig.h" - -ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); - - - ui.manditoryHardware->setVisible(false); - ui.frameTypeButton->setVisible(false); - ui.compassButton->setVisible(false); - ui.accelCalibrateButton->setVisible(false); - ui.arduPlaneLevelButton->setVisible(false); - ui.radioCalibrateButton->setVisible(false); - ui.optionalHardwareButton->setVisible(false); - ui.batteryMonitorButton->setVisible(false); - ui.sonarButton->setVisible(false); - ui.airspeedButton->setVisible(false); - ui.opticalFlowButton->setVisible(false); - ui.osdButton->setVisible(false); - ui.cameraGimbalButton->setVisible(false); - - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.radio3DRButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.batteryMonitorButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.sonarButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.opticalFlowButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.osdButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.cameraGimbalButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.antennaTrackerButton,SLOT(setVisible(bool))); - - connect(ui.frameTypeButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - - m_apmFirmwareConfig = new ApmFirmwareConfig(this); - ui.stackedWidget->addWidget(m_apmFirmwareConfig); //Firmware placeholder. - m_buttonToConfigWidgetMap[ui.firmwareButton] = m_apmFirmwareConfig; - connect(ui.firmwareButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_frameConfig = new FrameTypeConfig(this); - ui.stackedWidget->addWidget(m_frameConfig); - m_buttonToConfigWidgetMap[ui.frameTypeButton] = m_frameConfig; - connect(ui.frameTypeButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_compassConfig = new CompassConfig(this); - ui.stackedWidget->addWidget(m_compassConfig); - m_buttonToConfigWidgetMap[ui.compassButton] = m_compassConfig; - connect(ui.compassButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_accelConfig = new AccelCalibrationConfig(this); - ui.stackedWidget->addWidget(m_accelConfig); - m_buttonToConfigWidgetMap[ui.accelCalibrateButton] = m_accelConfig; - connect(ui.accelCalibrateButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_planeLevel = new ApmPlaneLevel(this); - ui.stackedWidget->addWidget(m_planeLevel); - m_buttonToConfigWidgetMap[ui.arduPlaneLevelButton] = m_planeLevel; - connect(ui.arduPlaneLevelButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_radioConfig = new RadioCalibrationConfig(this); - ui.stackedWidget->addWidget(m_radioConfig); - m_buttonToConfigWidgetMap[ui.radioCalibrateButton] = m_radioConfig; - connect(ui.radioCalibrateButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - - m_radio3drConfig = new Radio3DRConfig(this); - ui.stackedWidget->addWidget(m_radio3drConfig); - m_buttonToConfigWidgetMap[ui.radio3DRButton] = m_radio3drConfig; - connect(ui.radio3DRButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_batteryConfig = new BatteryMonitorConfig(this); - ui.stackedWidget->addWidget(m_batteryConfig); - m_buttonToConfigWidgetMap[ui.batteryMonitorButton] = m_batteryConfig; - connect(ui.batteryMonitorButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_sonarConfig = new SonarConfig(this); - ui.stackedWidget->addWidget(m_sonarConfig); - m_buttonToConfigWidgetMap[ui.sonarButton] = m_sonarConfig; - connect(ui.sonarButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_airspeedConfig = new AirspeedConfig(this); - ui.stackedWidget->addWidget(m_airspeedConfig); - m_buttonToConfigWidgetMap[ui.airspeedButton] = m_airspeedConfig; - connect(ui.airspeedButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_opticalFlowConfig = new OpticalFlowConfig(this); - ui.stackedWidget->addWidget(m_opticalFlowConfig); - m_buttonToConfigWidgetMap[ui.opticalFlowButton] = m_opticalFlowConfig; - connect(ui.opticalFlowButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_osdConfig = new OsdConfig(this); - ui.stackedWidget->addWidget(m_osdConfig); - m_buttonToConfigWidgetMap[ui.osdButton] = m_osdConfig; - connect(ui.osdButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_cameraGimbalConfig = new CameraGimbalConfig(this); - ui.stackedWidget->addWidget(m_cameraGimbalConfig); - m_buttonToConfigWidgetMap[ui.cameraGimbalButton] = m_cameraGimbalConfig; - connect(ui.cameraGimbalButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_antennaTrackerConfig = new AntennaTrackerConfig(this); - ui.stackedWidget->addWidget(m_antennaTrackerConfig); - m_buttonToConfigWidgetMap[ui.antennaTrackerButton] = m_antennaTrackerConfig; - connect(ui.antennaTrackerButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*))); - if (UASManager::instance()->getActiveUAS()) - { - activeUASSet(UASManager::instance()->getActiveUAS()); - } -} -void ApmHardwareConfig::activateStackedWidget() -{ - if (m_buttonToConfigWidgetMap.contains(sender())) - { - ui.stackedWidget->setCurrentWidget(m_buttonToConfigWidgetMap[sender()]); - } -} - -ApmHardwareConfig::~ApmHardwareConfig() -{ -} - -void ApmHardwareConfig::activeUASSet(UASInterface *uas) -{ - if (!uas) - { - return; - } - if (uas->getSystemType() == MAV_TYPE_FIXED_WING) - { - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.arduPlaneLevelButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setVisible(bool))); - connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.airspeedButton,SLOT(setVisible(bool))); - } - else if (uas->getSystemType() == MAV_TYPE_QUADROTOR) - { - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.frameTypeButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.accelCalibrateButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setVisible(bool))); - } - else if (uas->getSystemType() == MAV_TYPE_GROUND_ROVER) - { - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setVisible(bool))); - } - else - { - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setVisible(bool))); - connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setVisible(bool))); - } - ui.firmwareButton->setVisible(true); - ui.manditoryHardware->setVisible(true); - ui.manditoryHardware->setChecked(true); - ui.optionalHardwareButton->setVisible(true); - ui.optionalHardwareButton->setChecked(true); -} diff --git a/src/ui/configuration/ApmHardwareConfig.h b/src/ui/configuration/ApmHardwareConfig.h deleted file mode 100644 index 427403b6d9ac8c1b35f8d6ea29b193503ae4bc48..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmHardwareConfig.h +++ /dev/null @@ -1,88 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2013 Michael Carpenter (malcom2073@gmail.com) - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief APM Hardware Configuration widget header. - * - * @author Michael Carpenter - * - */ - -#ifndef APMHARDWARECONFIG_H -#define APMHARDWARECONFIG_H - -#include -#include "ui_ApmHardwareConfig.h" -#include -#include -#include "FrameTypeConfig.h" -#include "CompassConfig.h" -#include "AccelCalibrationConfig.h" -#include "RadioCalibrationConfig.h" -#include "Radio3DRConfig.h" -#include "BatteryMonitorConfig.h" -#include "SonarConfig.h" -#include "AirspeedConfig.h" -#include "OpticalFlowConfig.h" -#include "OsdConfig.h" -#include "CameraGimbalConfig.h" -#include "AntennaTrackerConfig.h" -#include "ApmPlaneLevel.h" -#include "ApmFirmwareConfig.h" - -class ApmHardwareConfig : public QWidget -{ - Q_OBJECT - -public: - explicit ApmHardwareConfig(QWidget *parent = 0); - ~ApmHardwareConfig(); -private: - QPointer m_frameConfig; - QPointer m_compassConfig; - QPointer m_accelConfig; - QPointer m_radioConfig; - - QPointer m_apmFirmwareConfig; - QPointer m_radio3drConfig; - QPointer m_batteryConfig; - QPointer m_sonarConfig; - QPointer m_airspeedConfig; - QPointer m_opticalFlowConfig; - QPointer m_osdConfig; - QPointer m_cameraGimbalConfig; - QPointer m_antennaTrackerConfig; - QPointer m_planeLevel; - -private slots: - void activeUASSet(UASInterface *uas); - void activateStackedWidget(); -private: - Ui::ApmHardwareConfig ui; - - //This is a map between the buttons, and the widgets they should be displying - QMap m_buttonToConfigWidgetMap; -}; - -#endif // APMHARDWARECONFIG_H diff --git a/src/ui/configuration/ApmHardwareConfig.ui b/src/ui/configuration/ApmHardwareConfig.ui deleted file mode 100644 index e4a711b060d08d3c1cb58b395d54e9341587cb41..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmHardwareConfig.ui +++ /dev/null @@ -1,330 +0,0 @@ - - - ApmHardwareConfig - - - - 0 - 0 - 1225 - 827 - - - - Form - - - - - 0 - 20 - 175 - 531 - - - - - 175 - 0 - - - - - 175 - 16777215 - - - - true - - - - - 0 - 0 - 156 - 676 - - - - - - - QLayout::SetMinAndMaxSize - - - - - - 100 - 35 - - - - Install Firmware - - - - - - - - 0 - 35 - - - - >>> Manditory Hardware - - - true - - - - - - - - 0 - 35 - - - - Qt::LeftToRight - - - Frame Type - - - - - - - - 0 - 35 - - - - Compass - - - - - - - - 0 - 35 - - - - Qt::LeftToRight - - - false - - - Accel Calibration - - - - - - - - 0 - 35 - - - - Qt::LeftToRight - - - false - - - ArduPlane Level - - - - - - - - 100 - 35 - - - - - 16777215 - 16777215 - - - - Radio Calibration - - - false - - - false - - - - - - - - 0 - 35 - - - - >>> Optional Hardware - - - true - - - - - - - - 0 - 35 - - - - 3DR Radio - - - - - - - - 0 - 35 - - - - Battery Monitor - - - - - - - - 0 - 35 - - - - Sonar - - - - - - - - 0 - 35 - - - - Airspeed - - - - - - - - 0 - 35 - - - - Optical Flow - - - - - - - - 0 - 35 - - - - OSD - - - - - - - - 0 - 35 - - - - Camera Gimbal - - - - - - - - 0 - 35 - - - - Antenna Tracker - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - 200 - 30 - 921 - 761 - - - - -1 - - - - - - diff --git a/src/ui/configuration/ApmPlaneLevel.cc b/src/ui/configuration/ApmPlaneLevel.cc deleted file mode 100644 index 3bda80e928a29c71d315b8eeef068b06002a26cc..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmPlaneLevel.cc +++ /dev/null @@ -1,69 +0,0 @@ -#include "ApmPlaneLevel.h" -#include - -ApmPlaneLevel::ApmPlaneLevel(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - connect(ui.levelPushButton,SIGNAL(clicked()),this,SLOT(levelClicked())); - connect(ui.manualLevelCheckBox,SIGNAL(toggled(bool)),this,SLOT(manualCheckBoxToggled(bool))); - initConnections(); -} - -ApmPlaneLevel::~ApmPlaneLevel() -{ -} -void ApmPlaneLevel::levelClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - QMessageBox::information(0,"Warning","Be sure the plane is completly level, then click ok"); - MAV_CMD command = MAV_CMD_PREFLIGHT_CALIBRATION; - int confirm = 0; - float param1 = 1.0; - float param2 = 0.0; - float param3 = 1.0; - float param4 = 0.0; - float param5 = 0.0; - float param6 = 0.0; - float param7 = 0.0; - int component = 1; - m_uas->executeCommand(command, confirm, param1, param2, param3, param4, param5, param6, param7, component); - QMessageBox::information(0,"Warning","Leveling completed"); -} - -void ApmPlaneLevel::manualCheckBoxToggled(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->getParamManager()->setParameter(1,"MANUAL_LEVEL",1); - } - else - { - m_uas->getParamManager()->setParameter(1,"MANUAL_LEVEL",0); - } -} -void ApmPlaneLevel::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "MANUAL_LEVEL") - { - if (value.toInt() == 1) - { - ui.manualLevelCheckBox->setChecked(true); - } - else - { - ui.manualLevelCheckBox->setChecked(false); - } - } -} diff --git a/src/ui/configuration/ApmPlaneLevel.h b/src/ui/configuration/ApmPlaneLevel.h deleted file mode 100644 index a6a38078f3704b10a283126fc84a6aebfe8738bd..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmPlaneLevel.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef APMPLANELEVEL_H -#define APMPLANELEVEL_H - -#include -#include "ui_ApmPlaneLevel.h" -#include "AP2ConfigWidget.h" - -class ApmPlaneLevel : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit ApmPlaneLevel(QWidget *parent = 0); - ~ApmPlaneLevel(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void levelClicked(); - void manualCheckBoxToggled(bool checked); -private: - Ui::ApmPlaneLevel ui; -}; - -#endif // APMPLANELEVEL_H diff --git a/src/ui/configuration/ApmPlaneLevel.ui b/src/ui/configuration/ApmPlaneLevel.ui deleted file mode 100644 index ef22b19992f262acf776e84fbfca097e2074c997..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmPlaneLevel.ui +++ /dev/null @@ -1,99 +0,0 @@ - - - ApmPlaneLevel - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - 10 - 10 - 141 - 31 - - - - <h2>ArduPlane Level</h2> - - - - - - 50 - 70 - 271 - 41 - - - - By Default your plane will autolevel on every boot. -To disable this action you need to turn on manual -level and perform a level to calibrate the accel offsets. - - - - - - 50 - 150 - 291 - 16 - - - - Level your plane and click Level to set default accel offsets - - - - - - 160 - 180 - 75 - 23 - - - - Level - - - - - - 120 - 230 - 151 - 51 - - - - For advanced users ONLY - - - - - 30 - 20 - 91 - 17 - - - - Manual Level - - - - - - - diff --git a/src/ui/configuration/ApmSoftwareConfig.cc b/src/ui/configuration/ApmSoftwareConfig.cc deleted file mode 100644 index a5308dab76eeeb3c8080336a93e99a012d2679a0..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmSoftwareConfig.cc +++ /dev/null @@ -1,368 +0,0 @@ -#include -#include -#include - -#include "ApmSoftwareConfig.h" - - -ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); - - ui.flightModesButton->setVisible(false); - ui.standardParamButton->setVisible(false); - ui.failSafeButton->setVisible(false); - ui.advancedParamButton->setVisible(false); - ui.advParamListButton->setVisible(false); - ui.arduCopterPidButton->setVisible(false); - ui.arduRoverPidButton->setVisible(false); - ui.arduPlanePidButton->setVisible(false); - - m_flightConfig = new FlightModeConfig(this); - ui.stackedWidget->addWidget(m_flightConfig); - m_buttonToConfigWidgetMap[ui.flightModesButton] = m_flightConfig; - connect(ui.flightModesButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_standardParamConfig = new StandardParamConfig(this); - ui.stackedWidget->addWidget(m_standardParamConfig); - m_buttonToConfigWidgetMap[ui.standardParamButton] = m_standardParamConfig; - connect(ui.standardParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_failSafeConfig = new FailSafeConfig(this); - ui.stackedWidget->addWidget(m_failSafeConfig); - m_buttonToConfigWidgetMap[ui.failSafeButton] = m_failSafeConfig; - connect(ui.failSafeButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_advancedParamConfig = new AdvancedParamConfig(this); - ui.stackedWidget->addWidget(m_advancedParamConfig); - m_buttonToConfigWidgetMap[ui.advancedParamButton] = m_advancedParamConfig; - connect(ui.advancedParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_advParameterList = new AdvParameterList(this); - ui.stackedWidget->addWidget(m_advParameterList); - m_buttonToConfigWidgetMap[ui.advParamListButton] = m_advParameterList; - connect(ui.advParamListButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_arduCopterPidConfig = new ArduCopterPidConfig(this); - ui.stackedWidget->addWidget(m_arduCopterPidConfig); - m_buttonToConfigWidgetMap[ui.arduCopterPidButton] = m_arduCopterPidConfig; - connect(ui.arduCopterPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_arduPlanePidConfig = new ArduPlanePidConfig(this); - ui.stackedWidget->addWidget(m_arduPlanePidConfig); - m_buttonToConfigWidgetMap[ui.arduPlanePidButton] = m_arduPlanePidConfig; - connect(ui.arduPlanePidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - m_arduRoverPidConfig = new ArduRoverPidConfig(this); - ui.stackedWidget->addWidget(m_arduRoverPidConfig); - m_buttonToConfigWidgetMap[ui.arduRoverPidButton] = m_arduRoverPidConfig; - connect(ui.arduRoverPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); - - connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*))); - activeUASSet(UASManager::instance()->getActiveUAS()); -} - -ApmSoftwareConfig::~ApmSoftwareConfig() -{ -} -void ApmSoftwareConfig::activateStackedWidget() -{ - if (m_buttonToConfigWidgetMap.contains(sender())) - { - ui.stackedWidget->setCurrentWidget(m_buttonToConfigWidgetMap[sender()]); - } -} -void ApmSoftwareConfig::activeUASSet(UASInterface *uas) -{ - if (!uas) - { - return; - } - - ui.flightModesButton->setVisible(true); - ui.standardParamButton->setVisible(true); - ui.failSafeButton->setVisible(true); - ui.advancedParamButton->setVisible(true); - ui.advParamListButton->setVisible(true); - - QString compare = ""; - if (uas->getSystemType() == MAV_TYPE_FIXED_WING) - { - ui.arduPlanePidButton->setVisible(true); - ui.arduCopterPidButton->setVisible(false); - ui.arduRoverPidButton->setVisible(false); - compare = "ArduPlane"; - } - else if (uas->getSystemType() == MAV_TYPE_QUADROTOR) - { - ui.arduCopterPidButton->setVisible(true); - ui.arduPlanePidButton->setVisible(false); - ui.arduRoverPidButton->setVisible(false); - compare = "ArduCopter"; - } - else if (uas->getSystemType() == MAV_TYPE_GROUND_ROVER) - { - ui.arduRoverPidButton->setVisible(true); - ui.arduCopterPidButton->setVisible(false); - ui.arduPlanePidButton->setVisible(false); - compare = "APMRover2"; - } - - - QDir autopilotdir(qApp->applicationDirPath() + "/files/" + uas->getAutopilotTypeName().toLower()); - QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml"); - if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly)) - { - return; - } - - QXmlStreamReader xml(xmlfile.readAll()); - xmlfile.close(); - - //TODO: Testing to ensure that incorrectly formated XML won't break this. - //Also, move this into the Param Manager, as it should handle all metadata. - while (!xml.atEnd()) - { - if (xml.isStartElement() && xml.name() == "paramfile") - { - xml.readNext(); - while ((xml.name() != "paramfile") && !xml.atEnd()) - { - QString valuetype = ""; - if (xml.isStartElement() && (xml.name() == "vehicles" || xml.name() == "libraries")) //Enter into the vehicles loop - { - valuetype = xml.name().toString(); - xml.readNext(); - while ((xml.name() != valuetype) && !xml.atEnd()) - { - if (xml.isStartElement() && xml.name() == "parameters") //This is a parameter block - { - QString parametersname = ""; - if (xml.attributes().hasAttribute("name")) - { - parametersname = xml.attributes().value("name").toString(); - } - - QVariantMap genset; - QVariantMap advset; - - QString setname = parametersname; - xml.readNext(); - int genarraycount = 0; - int advarraycount = 0; - while ((xml.name() != "parameters") && !xml.atEnd()) - { - if (xml.isStartElement() && xml.name() == "param") - { - QString humanname = xml.attributes().value("humanName").toString(); - QString name = xml.attributes().value("name").toString(); - QString tab= xml.attributes().value("user").toString(); - if (tab == "Advanced") - { - advset["title"] = parametersname; - } - else - { - genset["title"] = parametersname; - } - if (name.contains(":")) - { - name = name.split(":")[1]; - } - QString docs = xml.attributes().value("documentation").toString(); - //paramTooltips[name] = name + " - " + docs; - - int type = -1; //Type of item - QMap fieldmap; - QMap valuemap; - xml.readNext(); - while ((xml.name() != "param") && !xml.atEnd()) - { - if (xml.isStartElement() && xml.name() == "values") - { - type = 1; //1 is a combobox - if (tab == "Advanced") - { - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "COMBO"; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1; - } - else - { - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "COMBO"; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1; - } - int paramcount = 0; - xml.readNext(); - while ((xml.name() != "values") && !xml.atEnd()) - { - if (xml.isStartElement() && xml.name() == "value") - { - - QString code = xml.attributes().value("code").toString(); - QString arg = xml.readElementText(); - valuemap[code] = arg; - if (tab == "Advanced") - { - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt(); - } - else - { - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt(); - } - paramcount++; - } - xml.readNext(); - } - if (tab == "Advanced") - { - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount; - } - else - { - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount; - } - } - if (xml.isStartElement() && xml.name() == "field") - { - type = 2; //2 is a slider - QString fieldtype = xml.attributes().value("name").toString(); - QString text = xml.readElementText(); - fieldmap[fieldtype] = text; - } - xml.readNext(); - } - if (type == -1) - { - //Nothing inside! Assume it's a value, give it a default range. - type = 2; - QString fieldtype = "Range"; - QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges. - fieldmap[fieldtype] = text; - } - if (type == 2) - { - if (tab == "Advanced") - { - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "SLIDER"; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1; - } - else - { - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "SLIDER"; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1; - } - if (fieldmap.contains("Range")) - { - float min = 0; - float max = 0; - //Some range fields list "0-10" and some list "0 10". Handle both. - if (fieldmap["Range"].split(" ").size() > 1) - { - min = fieldmap["Range"].split(" ")[0].trimmed().toFloat(); - max = fieldmap["Range"].split(" ")[1].trimmed().toFloat(); - } - else if (fieldmap["Range"].split("-").size() > 1) - { - min = fieldmap["Range"].split("-")[0].trimmed().toFloat(); - max = fieldmap["Range"].split("-")[1].trimmed().toFloat(); - } - if (tab == "Advanced") - { - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min; - advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max; - } - else - { - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min; - genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max; - } - } - } - if (tab == "Advanced") - { - advarraycount++; - advset["count"] = advarraycount; - } - else - { - genarraycount++; - genset["count"] = genarraycount; - } - //Right here we have a single param in memory - if (valuemap.size() > 0) - { - QList > valuelist; - for (QMap::const_iterator i = valuemap.constBegin();i!=valuemap.constEnd();i++) - { - valuelist.append(QPair(i.key().toInt(),i.value())); - } - if (compare == parametersname) - { - if (tab == "Standard") - { - m_standardParamConfig->addCombo(humanname,docs,name,valuelist); - } - else if (tab == "Advanced") - { - m_advancedParamConfig->addCombo(humanname,docs,name,valuelist); - } - m_advParameterList->setParameterMetaData(name,humanname,docs); - } - } - else if (fieldmap.size() > 0) - { - float min = 0; - float max = 65535; - if (fieldmap.contains("Range")) - { - //Some range fields list "0-10" and some list "0 10". Handle both. - if (fieldmap["Range"].split(" ").size() > 1) - { - min = fieldmap["Range"].split(" ")[0].trimmed().toFloat(); - max = fieldmap["Range"].split(" ")[1].trimmed().toFloat(); - } - else if (fieldmap["Range"].split("-").size() > 1) - { - min = fieldmap["Range"].split("-")[0].trimmed().toFloat(); - max = fieldmap["Range"].split("-")[1].trimmed().toFloat(); - } - } - if (compare == parametersname) - { - if (tab == "Standard") - { - m_standardParamConfig->addRange(humanname,docs,name,min,max); - } - else if (tab == "Advanced") - { - m_advancedParamConfig->addRange(humanname,docs,name,min,max); - } - m_advParameterList->setParameterMetaData(name,humanname,docs); - } - } - - } - xml.readNext(); - } - } - xml.readNext(); - } - - } - xml.readNext(); - } - } - xml.readNext(); - } - -} diff --git a/src/ui/configuration/ApmSoftwareConfig.h b/src/ui/configuration/ApmSoftwareConfig.h deleted file mode 100644 index 77b97d0822c16eb72842b586ea06fa9c5a191c8a..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmSoftwareConfig.h +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef APMSOFTWARECONFIG_H -#define APMSOFTWARECONFIG_H - -#include -#include "ui_ApmSoftwareConfig.h" -#include "FlightModeConfig.h" -#include "BasicPidConfig.h" -#include "StandardParamConfig.h" -#include "GeoFenceConfig.h" -#include "FailSafeConfig.h" -#include "AdvancedParamConfig.h" -#include "ArduCopterPidConfig.h" -#include "ArduPlanePidConfig.h" -#include "ArduRoverPidConfig.h" -#include "AdvParameterList.h" -#include "UASInterface.h" -#include "UASManager.h" - -class ApmSoftwareConfig : public QWidget -{ - Q_OBJECT - -public: - explicit ApmSoftwareConfig(QWidget *parent = 0); - ~ApmSoftwareConfig(); -private slots: - void activateStackedWidget(); - void activeUASSet(UASInterface *uas); -private: - Ui::ApmSoftwareConfig ui; - QPointer m_basicPidConfig; - QPointer m_flightConfig; - QPointer m_standardParamConfig; - QPointer m_geoFenceConfig; - QPointer m_failSafeConfig; - QPointer m_advancedParamConfig; - QPointer m_arduCopterPidConfig; - QPointer m_arduPlanePidConfig; - QPointer m_arduRoverPidConfig; - QPointer m_advParameterList; - QMap m_buttonToConfigWidgetMap; -}; - -#endif // APMSOFTWARECONFIG_H diff --git a/src/ui/configuration/ApmSoftwareConfig.ui b/src/ui/configuration/ApmSoftwareConfig.ui deleted file mode 100644 index d3deec752896dd3f463a9e1fe4df8d2e1005d891..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ApmSoftwareConfig.ui +++ /dev/null @@ -1,210 +0,0 @@ - - - ApmSoftwareConfig - - - - 0 - 0 - 853 - 619 - - - - Form - - - - - - - 175 - 0 - - - - - 175 - 16777215 - - - - true - - - - - 0 - 0 - 173 - 599 - - - - - - - QLayout::SetMinAndMaxSize - - - - - - 100 - 35 - - - - qgroundcontrol 2.0 Config - - - - - - - - 0 - 35 - - - - Flight Modes - - - false - - - - - - - - 0 - 35 - - - - Standard Params - - - false - - - - - - - - 0 - 35 - - - - FailSafe - - - false - - - - - - - - 0 - 35 - - - - Advanced Params - - - false - - - - - - - - 0 - 35 - - - - Full Parameter List - - - false - - - - - - - - 0 - 35 - - - - ArduCopter Pids - - - false - - - - - - - - 0 - 35 - - - - ArduPlane Pids - - - - - - - - 0 - 35 - - - - ArduRover Pids - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - - - - - diff --git a/src/ui/configuration/ArduCopterPidConfig.cc b/src/ui/configuration/ArduCopterPidConfig.cc deleted file mode 100644 index 632d3d17c31407163570b9d148008e059855a92a..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduCopterPidConfig.cc +++ /dev/null @@ -1,210 +0,0 @@ -#include "ArduCopterPidConfig.h" - -ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - m_pitchRollLocked = false; - connect(ui.checkBox,SIGNAL(clicked(bool)),this,SLOT(lockCheckBoxClicked(bool))); - connect(ui.stabilPitchPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - connect(ui.stabilRollPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - connect(ui.stabilYawPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - m_nameToBoxMap["STB_RLL_P"] = ui.stabilPitchPSpinBox; - m_nameToBoxMap["STB_PIT_P"] = ui.stabilRollPSpinBox; - m_nameToBoxMap["STB_YAW_P"] = ui.stabilYawPSpinBox; - m_nameToBoxMap["HLD_LAT_P"] = ui.loiterPidPSpinBox; - - m_nameToBoxMap["RATE_RLL_P"] = ui.rateRollPSpinBox; - m_nameToBoxMap["RATE_RLL_I"] = ui.rateRollISpinBox; - m_nameToBoxMap["RATE_RLL_D"] = ui.rateRollDSpinBox; - m_nameToBoxMap["RATE_RLL_IMAX"] = ui.rateRollIMAXSpinBox; - - m_nameToBoxMap["RATE_PIT_P"] = ui.ratePitchPSpinBox; - m_nameToBoxMap["RATE_PIT_I"] = ui.ratePitchISpinBox; - m_nameToBoxMap["RATE_PIT_D"] = ui.ratePitchDSpinBox; - m_nameToBoxMap["RATE_PIT_IMAX"] = ui.ratePitchIMAXSpinBox; - - m_nameToBoxMap["RATE_YAW_P"] = ui.rateYawPSpinBox; - m_nameToBoxMap["RATE_YAW_I"] = ui.rateYawISpinBox; - m_nameToBoxMap["RATE_YAW_D"] = ui.rateYawDSpinBox; - m_nameToBoxMap["RATE_YAW_IMAX"] = ui.rateYawIMAXSpinBox; - - m_nameToBoxMap["LOITER_LAT_P"] = ui.rateLoiterPSpinBox; - m_nameToBoxMap["LOITER_LAT_I"] = ui.rateLoiterISpinBox; - m_nameToBoxMap["LOITER_LAT_D"] = ui.rateLoiterDSpinBox; - m_nameToBoxMap["LOITER_LAT_IMAX"] = ui.rateLoiterIMAXSpinBox; - - m_nameToBoxMap["THR_ACCEL_P"] = ui.throttleAccelPSpinBox; - m_nameToBoxMap["THR_ACCEL_I"] = ui.throttleAccelISpinBox; - m_nameToBoxMap["THR_ACCEL_D"] = ui.throttleAccelDSpinBox; - m_nameToBoxMap["THR_ACCEL_IMAX"] = ui.throttleAccelIMAXSpinBox; - - m_nameToBoxMap["THR_RATE_P"] = ui.throttleRatePSpinBox; - m_nameToBoxMap["THR_RATE_D"] = ui.throttleDateDSpinBox; - - m_nameToBoxMap["THR_ALT_P"] = ui.altitudeHoldPSpinBox; - - m_nameToBoxMap["WPNAV_SPEED"] = ui.wpNavLoiterSpeedSpinBox; - m_nameToBoxMap["WPNAV_RADIUS"] = ui.wpNavRadiusSpinBox; - m_nameToBoxMap["WPNAV_SPEED_DN"] = ui.wpNavSpeedDownSpinBox; - m_nameToBoxMap["WPNAV_LOIT_SPEED"] = ui.wpNavSpeedSpinBox; - m_nameToBoxMap["WPNAV_SPEED_UP"] = ui.wpNavSpeedUpSpinBox; - - m_nameToBoxMap["TUNE_HIGH"] = ui.ch6MaxSpinBox; - m_nameToBoxMap["TUNE_LOW"] = ui.ch6MinSpinBox; - - connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked())); - connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked())); - - - - m_ch6ValueToTextList.append(QPair(0,"CH6_NONE")); - m_ch6ValueToTextList.append(QPair(1,"CH6_STABILIZE_KP")); - m_ch6ValueToTextList.append(QPair(2,"CH6_STABILIZE_KI")); - m_ch6ValueToTextList.append(QPair(3,"CH6_YAW_KP")); - m_ch6ValueToTextList.append(QPair(24,"CH6_YAW_KI")); - m_ch6ValueToTextList.append(QPair(4,"CH6_RATE_KP")); - m_ch6ValueToTextList.append(QPair(5,"CH6_RATE_KI")); - m_ch6ValueToTextList.append(QPair(6,"CH6_YAW_RATE_KP")); - m_ch6ValueToTextList.append(QPair(26,"CH6_YAW_RATE_KD")); - m_ch6ValueToTextList.append(QPair(7,"CH6_THROTTLE_KP")); - m_ch6ValueToTextList.append(QPair(9,"CH6_RELAY")); - m_ch6ValueToTextList.append(QPair(10,"CH6_WP_SPEED")); - m_ch6ValueToTextList.append(QPair(12,"CH6_LOITER_KP")); - m_ch6ValueToTextList.append(QPair(13,"CH6_HELI_EXTERNAL_GYRO")); - m_ch6ValueToTextList.append(QPair(14,"CH6_THR_HOLD_KP")); - m_ch6ValueToTextList.append(QPair(17,"CH6_OPTFLOW_KP")); - m_ch6ValueToTextList.append(QPair(18,"CH6_OPTFLOW_KI")); - m_ch6ValueToTextList.append(QPair(19,"CH6_OPTFLOW_KD")); - m_ch6ValueToTextList.append(QPair(21,"CH6_RATE_KD")); - m_ch6ValueToTextList.append(QPair(22,"CH6_LOITER_RATE_KP")); - m_ch6ValueToTextList.append(QPair(23,"CH6_LOITER_RATE_KD")); - m_ch6ValueToTextList.append(QPair(25,"CH6_ACRO_KP")); - m_ch6ValueToTextList.append(QPair(27,"CH6_LOITER_KI")); - m_ch6ValueToTextList.append(QPair(28,"CH6_LOITER_RATE_KI")); - m_ch6ValueToTextList.append(QPair(29,"CH6_STABILIZE_KD")); - m_ch6ValueToTextList.append(QPair(30,"CH6_AHRS_YAW_KP")); - m_ch6ValueToTextList.append(QPair(31,"CH6_AHRS_KP")); - m_ch6ValueToTextList.append(QPair(32,"CH6_INAV_TC")); - m_ch6ValueToTextList.append(QPair(33,"CH6_THROTTLE_KI")); - m_ch6ValueToTextList.append(QPair(34,"CH6_THR_ACCEL_KP")); - m_ch6ValueToTextList.append(QPair(35,"CH6_THR_ACCEL_KI")); - m_ch6ValueToTextList.append(QPair(36,"CH6_THR_ACCEL_KD")); - m_ch6ValueToTextList.append(QPair(38,"CH6_DECLINATION")); - m_ch6ValueToTextList.append(QPair(39,"CH6_CIRCLE_RATE")); - for (int i=0;iaddItem(m_ch6ValueToTextList[i].second); - } - - m_ch78ValueToTextList.append(QPair(0,"Do nothing")); - m_ch78ValueToTextList.append(QPair(2,"Flip")); - m_ch78ValueToTextList.append(QPair(3,"Simple mode")); - m_ch78ValueToTextList.append(QPair(4,"RTL")); - m_ch78ValueToTextList.append(QPair(5,"Save Trim")); - m_ch78ValueToTextList.append(QPair(7,"Save WP")); - m_ch78ValueToTextList.append(QPair(8,"Multi Mode")); - m_ch78ValueToTextList.append(QPair(9,"Camera Trigger")); - m_ch78ValueToTextList.append(QPair(10,"Sonar")); - m_ch78ValueToTextList.append(QPair(11,"Fence")); - m_ch78ValueToTextList.append(QPair(12,"ResetToArmedYaw")); - for (int i=0;iaddItem(m_ch78ValueToTextList[i].second); - ui.ch8OptComboBox->addItem(m_ch78ValueToTextList[i].second); - } - initConnections(); -} -void ArduCopterPidConfig::lockCheckBoxClicked(bool checked) -{ - m_pitchRollLocked = checked; -} -void ArduCopterPidConfig::stabilLockedChanged(double value) -{ - if (m_pitchRollLocked) - { - disconnect(ui.stabilPitchPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - disconnect(ui.stabilRollPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - disconnect(ui.stabilYawPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - ui.stabilPitchPSpinBox->setValue(value); - ui.stabilRollPSpinBox->setValue(value); - ui.stabilYawPSpinBox->setValue(value); - connect(ui.stabilPitchPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - connect(ui.stabilRollPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - connect(ui.stabilYawPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double))); - } -} - -ArduCopterPidConfig::~ArduCopterPidConfig() -{ -} -void ArduCopterPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (m_nameToBoxMap.contains(parameterName)) - { - m_nameToBoxMap[parameterName]->setValue(value.toDouble()); - } - else if (parameterName == "TUNE") - { - for (int i=0;isetCurrentIndex(i); - } - } - } - else if (parameterName == "CH7_OPT") - { - for (int i=0;isetCurrentIndex(i); - } - } - } - else if (parameterName == "CH8_OPT") - { - for (int i=0;isetCurrentIndex(i); - } - } - } -} -void ArduCopterPidConfig::writeButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - for (QMap::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++) - { - m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value()); - } - m_uas->getParamManager()->setParameter(1,"TUNE",m_ch78ValueToTextList[ui.ch6OptComboBox->currentIndex()].first); - m_uas->getParamManager()->setParameter(1,"CH7_OPT",m_ch78ValueToTextList[ui.ch7OptComboBox->currentIndex()].first); - m_uas->getParamManager()->setParameter(1,"CH8_OPT",m_ch78ValueToTextList[ui.ch8OptComboBox->currentIndex()].first); -} - -void ArduCopterPidConfig::refreshButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - for (QMap::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++) - { - m_uas->getParamManager()->requestParameterUpdate(1,i.key()); - } - m_uas->getParamManager()->requestParameterUpdate(1,"TUNE"); - m_uas->getParamManager()->requestParameterUpdate(1,"CH7_OPT"); - m_uas->getParamManager()->requestParameterUpdate(1,"CH8_OPT"); -} diff --git a/src/ui/configuration/ArduCopterPidConfig.h b/src/ui/configuration/ArduCopterPidConfig.h deleted file mode 100644 index d8a1360b882e67f07e31283ae9e17ed8557538ac..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduCopterPidConfig.h +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef ARDUCOPTERPIDCONFIG_H -#define ARDUCOPTERPIDCONFIG_H - -#include -#include "ui_ArduCopterPidConfig.h" - -#include "AP2ConfigWidget.h" - -class ArduCopterPidConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit ArduCopterPidConfig(QWidget *parent = 0); - ~ArduCopterPidConfig(); -private slots: - void writeButtonClicked(); - void refreshButtonClicked(); - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void lockCheckBoxClicked(bool checked); - void stabilLockedChanged(double value); -private: - bool m_pitchRollLocked; - QList > m_ch6ValueToTextList; - QList > m_ch78ValueToTextList; - QMap m_nameToBoxMap; - Ui::ArduCopterPidConfig ui; -}; - -#endif // ARDUCOPTERPIDCONFIG_H diff --git a/src/ui/configuration/ArduCopterPidConfig.ui b/src/ui/configuration/ArduCopterPidConfig.ui deleted file mode 100644 index 351ce51ed24e4463b9c9ac508fe2bea5c50730df..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduCopterPidConfig.ui +++ /dev/null @@ -1,1061 +0,0 @@ - - - ArduCopterPidConfig - - - - 0 - 0 - 750 - 596 - - - - Form - - - - - 20 - 10 - 181 - 51 - - - - <h2>ArduCopter Pids</h2> - - - - - - 120 - 540 - 75 - 23 - - - - Write Params - - - - - - 220 - 540 - 91 - 23 - - - - Refresh Params - - - - - - 10 - 70 - 695 - 401 - - - - - - - Rate Yaw - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Loiter PID - - - - - - - - - - P - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Rate Pitch - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Stabilize Roll - - - - - - - - - - P - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Stabilize Pitch - - - - - - - - - - P - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - - - - - - - - Rate Roll - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Altitude Hold - - - - - - - - - - P - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Stabilize Yaw - - - - - - - - - - P - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Rate Loiter - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Lock Pitch and Roll Values - - - - - - - - - - - Ch6 Opt - - - - - - - - - - - - - - Min - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - Max - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - Ch7 Opt - - - - - - - - - - - - - - Ch8 Opt - - - - - - - - - - - - - - Throttle Accel - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - Throttle Rate - - - - - - - - - - P - - - - - - - D - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - WPNav (cm's) - - - - - - - - - - Speed - - - - - - - Radius - - - - - - - Speed Up - - - - - - - speed Down - - - - - - - Loiter Speed - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - - - diff --git a/src/ui/configuration/ArduPlanePidConfig.cc b/src/ui/configuration/ArduPlanePidConfig.cc deleted file mode 100644 index 13db80b961ce4281d6aa55391352c483d3171c1c..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduPlanePidConfig.cc +++ /dev/null @@ -1,102 +0,0 @@ -#include "ArduPlanePidConfig.h" - - -ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - - m_nameToBoxMap["RLL2SRV_P"] = ui.servoRollPSpinBox; - m_nameToBoxMap["RLL2SRV_I"] = ui.servoRollISpinBox; - m_nameToBoxMap["RLL2SRV_D"] = ui.servoRollDSpinBox; - m_nameToBoxMap["RLL2SRV_IMAX"] = ui.servoRollIMAXSpinBox; - - m_nameToBoxMap["PTCH2SRV_P"] = ui.servoPitchPSpinBox; - m_nameToBoxMap["PTCH2SRV_I"] = ui.servoPitchISpinBox; - m_nameToBoxMap["PTCH2SRV_D"] = ui.servoPitchDSpinBox; - m_nameToBoxMap["PTCH2SRV_IMAX"] = ui.servoPitchIMAXSpinBox; - - m_nameToBoxMap["YW2SRV_P"] = ui.servoYawPSpinBox; - m_nameToBoxMap["YW2SRV_I"] = ui.servoYawISpinBox; - m_nameToBoxMap["YW2SRV_D"] = ui.servoYawDSpinBox; - m_nameToBoxMap["YW2SRV_IMAX"] = ui.servoYawIMAXSpinBox; - - m_nameToBoxMap["ALT2PTCH_P"] = ui.navAltPSpinBox; - m_nameToBoxMap["ALT2PTCH_I"] = ui.navAltISpinBox; - m_nameToBoxMap["ALT2PTCH_D"] = ui.navAltDSpinBox; - m_nameToBoxMap["ALT2PTCH_IMAX"] = ui.navAltIMAXSpinBox; - - m_nameToBoxMap["ARSP2PTCH_P"] = ui.navASPSpinBox; - m_nameToBoxMap["ARSP2PTCH_I"] = ui.navASISpinBox; - m_nameToBoxMap["ARSP2PTCH_D"] = ui.navASDSpinBox; - m_nameToBoxMap["ARSP2PTCH_IMAX"] = ui.navASIMAXSpinBox; - - m_nameToBoxMap["ENRGY2THR_P"] = ui.energyPSpinBox; - m_nameToBoxMap["ENRGY2THR_I"] = ui.energyISpinBox; - m_nameToBoxMap["ENRGY2THR_D"] = ui.energyDSpinBox; - m_nameToBoxMap["ENRGY2THR_IMAX"] = ui.energyIMAXSpinBox; - - m_nameToBoxMap["KFF_PTCH2THR"] = ui.otherPitchCompSpinBox; - m_nameToBoxMap["KFF_PTCHCOMP"] = ui.otherPtTSpinBox; - m_nameToBoxMap["KFF_RDDRMIX"] = ui.otherRudderMixSpinBox; - - m_nameToBoxMap["TRIM_THROTTLE"] = ui.throttleCruiseSpinBox; - m_nameToBoxMap["THR_FS_VALUE"] = ui.throttleFSSpinBox; - m_nameToBoxMap["THR_MAX"] = ui.throttleMaxSpinBox; - m_nameToBoxMap["THR_MIN"] = ui.throttleMinSpinBox; - - m_nameToBoxMap["TRIM_ARSPD_CM"] = ui.airspeedCruiseSpinBox; - m_nameToBoxMap["ARSPD_FBW_MAX"] = ui.airspeedFBWMaxSpinBox; - m_nameToBoxMap["ARSPD_FBW_MIN"] = ui.airspeedFBWMinSpinBox; - m_nameToBoxMap["ARSPD_RATIO"] = ui.airspeedRatioSpinBox; - - m_nameToBoxMap["NAVL1_DAMPING"] = ui.l1DampingSpinBox; - m_nameToBoxMap["NAVL1_PERIOD"] = ui.l1PeriodSpinBox; - - m_nameToBoxMap["LIM_ROLL_CD"] = ui.navBankMaxSpinBox; - m_nameToBoxMap["LIM_PITCH_MAX"] = ui.navPitchMaxSpinBox; - m_nameToBoxMap["LIM_PITCH_MIN"] = ui.navPitchMinSpinBox; - - connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked())); - connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked())); - initConnections(); -} - -ArduPlanePidConfig::~ArduPlanePidConfig() -{ -} -void ArduPlanePidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (m_nameToBoxMap.contains(parameterName)) - { - m_nameToBoxMap[parameterName]->setValue(value.toDouble()); - } -} -void ArduPlanePidConfig::writeButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - for (QMap::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++) - { - m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value()); - } -} - -void ArduPlanePidConfig::refreshButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - for (QMap::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++) - { - m_uas->getParamManager()->requestParameterUpdate(1,i.key()); - } - -} diff --git a/src/ui/configuration/ArduPlanePidConfig.h b/src/ui/configuration/ArduPlanePidConfig.h deleted file mode 100644 index 3a254cb37198ec3dcb85d75f03790aabb14cb78b..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduPlanePidConfig.h +++ /dev/null @@ -1,24 +0,0 @@ -#ifndef ARDUPLANEPIDCONFIG_H -#define ARDUPLANEPIDCONFIG_H - -#include -#include "ui_ArduPlanePidConfig.h" -#include "AP2ConfigWidget.h" - -class ArduPlanePidConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit ArduPlanePidConfig(QWidget *parent = 0); - ~ArduPlanePidConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void writeButtonClicked(); - void refreshButtonClicked(); -private: - QMap m_nameToBoxMap; - Ui::ArduPlanePidConfig ui; -}; - -#endif // ARDUPLANEPIDCONFIG_H diff --git a/src/ui/configuration/ArduPlanePidConfig.ui b/src/ui/configuration/ArduPlanePidConfig.ui deleted file mode 100644 index 4ee4c406b15f97f025969bdefc401c22fe9a3fd6..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduPlanePidConfig.ui +++ /dev/null @@ -1,963 +0,0 @@ - - - ArduPlanePidConfig - - - - 0 - 0 - 733 - 641 - - - - Form - - - - - 20 - 10 - 681 - 581 - - - - - - - L1 Control - Turn Control - - - - - - - - - - Period - - - - - - - Damping - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - Servo Roll Pid - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 10000.000000000000000 - - - - - - - - - - - - - - Nav Pitch Alt Pid - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 10000.000000000000000 - - - - - - - - - - - - - - Nav Pitch AS Pid - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 10000.000000000000000 - - - - - - - - - - - - - - Servo Yaw Pid - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 10000.000000000000000 - - - - - - - - - - - - - - Throttle 0-100% - - - - - - - - - - Cruise - - - - - - - Min - - - - - - - Max - - - - - - - FS Value - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 10000.000000000000000 - - - - - - - - - - - - - - Servo Pitch Pid - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 10000.000000000000000 - - - - - - - - - - - - - - Aiespeed m/s - - - - - - - - - - Cruise - - - - - - - FBW min - - - - - - - FBW max - - - - - - - Ratio - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 100.000000000000000 - - - - - - - - - - - - - - Other Mix's - - - - - - - - - - P to T - - - - - - - Pitch Comp - - - - - - - Rudder Mix - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - - - - - - - - Navigation Angles - - - - - - - - - - Bank Max - - - - - - - Pitch Max - - - - - - - Pitch Min - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - 10000.000000000000000 - - - 0.000000000000000 - - - - - - - - - - - - - - Energy/Alt Pid - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 3 - - - 100.000000000000000 - - - - - - - 100.000000000000000 - - - - - - - - - - - - - - - - 260 - 600 - 75 - 23 - - - - Write Params - - - - - - 350 - 600 - 75 - 23 - - - - Refresh Params - - - - - - diff --git a/src/ui/configuration/ArduRoverPidConfig.cc b/src/ui/configuration/ArduRoverPidConfig.cc deleted file mode 100644 index 026bb83507829987c3fc1acf903c088f75d2709e..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduRoverPidConfig.cc +++ /dev/null @@ -1,83 +0,0 @@ -#include "ArduRoverPidConfig.h" - - -ArduRoverPidConfig::ArduRoverPidConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - nameToBoxMap["STEER2SRV_P"] = ui.steer2ServoPSpinBox; - nameToBoxMap["STEER2SRV_I"] = ui.steer2ServoISpinBox; - nameToBoxMap["STEER2SRV_D"] = ui.steer2ServoDSpinBox; - nameToBoxMap["STEER2SRV_IMAX"] = ui.steer2ServoIMAXSpinBox; - - nameToBoxMap["XTRK_ANGLE_CD"] = ui.xtrackEntryAngleSpinBox; - nameToBoxMap["XTRK_GAIN_SC"] = ui.xtrackGainSpinBox; - - nameToBoxMap["CRUISE_THROTTLE"] = ui.throttleCruiseSpinBox; - nameToBoxMap["THR_MIN"] = ui.throttleMinSpinBox; - nameToBoxMap["THR_MAX"] = ui.throttleMaxSpinBox; - nameToBoxMap["FS_THR_VALUE"] = ui.throttleFSSpinBox; - - nameToBoxMap["HDNG2STEER_P"] = ui.heading2SteerPSpinBox; - nameToBoxMap["HDNG2STEER_I"] = ui.heading2SteerISpinBox; - nameToBoxMap["HDNG2STEER_D"] = ui.heading2SteerDSpinBox; - nameToBoxMap["HDNG2STEER_IMAX"] = ui.heading2SteerIMAXSpinBox; - - nameToBoxMap["SPEED2THR_P"] = ui.speed2ThrottlePSpinBox; - nameToBoxMap["SPEED2THR_I"] = ui.speed2ThrottleISpinBox; - nameToBoxMap["SPEED2THR_D"] = ui.speed2ThrottleDSpinBox; - nameToBoxMap["SPEED2THR_IMAX"] = ui.speed2ThrottleIMAXSpinBox; - - nameToBoxMap["CRUISE_SPEED"] = ui.roverCruiseSpinBox; - nameToBoxMap["SPEED_TURN_GAIN"] = ui.roverTurnSpeedSpinBox; - nameToBoxMap["SPEED_TURN_DIST"] = ui.roverTurnDistSpinBox; - nameToBoxMap["WP_RADIUS"] = ui.roverWPRadiusSpinBox; - - nameToBoxMap["SONAR_TRIGGER_CM"] = ui.sonarTriggerSpinBox; - nameToBoxMap["SONAR_TURN_ANGLE"] = ui.sonarTurnAngleSpinBox; - nameToBoxMap["SONAR_TURN_TIME"] = ui.sonarTurnTimeSpinBox; - nameToBoxMap["SONAR_DEBOUNCE"] = ui.sonaeDebounceSpinBox; - - connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked())); - connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked())); - initConnections(); -} - -ArduRoverPidConfig::~ArduRoverPidConfig() -{ -} -void ArduRoverPidConfig::writeButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++) - { - m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value()); - } -} - -void ArduRoverPidConfig::refreshButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++) - { - m_uas->getParamManager()->requestParameterUpdate(1,i.key()); - } -} - -void ArduRoverPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (nameToBoxMap.contains(parameterName)) - { - nameToBoxMap[parameterName]->setValue(value.toFloat()); - } -} diff --git a/src/ui/configuration/ArduRoverPidConfig.h b/src/ui/configuration/ArduRoverPidConfig.h deleted file mode 100644 index 214658bdccf2f45dc8e450a2da29e81f60876e49..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduRoverPidConfig.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef ARDUROVERPIDCONFIG_H -#define ARDUROVERPIDCONFIG_H - -#include -#include "ui_ArduRoverPidConfig.h" -#include "AP2ConfigWidget.h" -class ArduRoverPidConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit ArduRoverPidConfig(QWidget *parent = 0); - ~ArduRoverPidConfig(); -private slots: - void writeButtonClicked(); - void refreshButtonClicked(); - void parameterChanged(int uas, int component, QString parameterName, QVariant value); -private: - QMap nameToBoxMap; - Ui::ArduRoverPidConfig ui; -}; - -#endif // ARDUROVERPIDCONFIG_H diff --git a/src/ui/configuration/ArduRoverPidConfig.ui b/src/ui/configuration/ArduRoverPidConfig.ui deleted file mode 100644 index 47831616e0adbd2578e60934c450c831c1ea7ce3..0000000000000000000000000000000000000000 --- a/src/ui/configuration/ArduRoverPidConfig.ui +++ /dev/null @@ -1,732 +0,0 @@ - - - ArduRoverPidConfig - - - - 0 - 0 - 626 - 607 - - - - Form - - - - - 10 - 10 - 151 - 21 - - - - <h2>ArduRover Pids</h2> - - - - - - 60 - 90 - 504 - 419 - - - - - - - Steer 2 Servo - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Speed 2 Throttle - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Heading 2 Steer - - - - - - - - - - P - - - - - - - I - - - - - - - D - - - - - - - INT_MAX - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Throttle 0-100% - - - - - - - - - - Cruise - - - - - - - Min - - - - - - - Max - - - - - - - FS Value - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Xtrack Pids - - - - - - - - - - Gain (cm) - - - - - - - Entry Angle - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - Sonar - - - - - - - - - - Trigger cm - - - - - - - Turn Angle - - - - - - - Turn Time - - - - - - - Debounce - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - Rover - - - - - - - - - - Cruise Speed - - - - - - - Turn Speed - - - - - - - Turn Dist - - - - - - - WP Radius - - - - - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - 3 - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - -10000.000000000000000 - - - 10000.000000000000000 - - - - - - - - - - - - - - - - 300 - 540 - 91 - 23 - - - - Refresh Params - - - - - - 200 - 540 - 75 - 23 - - - - Write Params - - - - - - diff --git a/src/ui/configuration/BasicPidConfig.cc b/src/ui/configuration/BasicPidConfig.cc deleted file mode 100644 index 938940e5f0912b7363f36f708c0b7a55b3700089..0000000000000000000000000000000000000000 --- a/src/ui/configuration/BasicPidConfig.cc +++ /dev/null @@ -1,11 +0,0 @@ -#include "BasicPidConfig.h" - - -BasicPidConfig::BasicPidConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); -} - -BasicPidConfig::~BasicPidConfig() -{ -} diff --git a/src/ui/configuration/BasicPidConfig.h b/src/ui/configuration/BasicPidConfig.h deleted file mode 100644 index 3129239416bbd244b7e5547b5d03c0adb42e3c67..0000000000000000000000000000000000000000 --- a/src/ui/configuration/BasicPidConfig.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef BASICPIDCONFIG_H -#define BASICPIDCONFIG_H - -#include -#include "ui_BasicPidConfig.h" - -class BasicPidConfig : public QWidget -{ - Q_OBJECT - -public: - explicit BasicPidConfig(QWidget *parent = 0); - ~BasicPidConfig(); - -private: - Ui::BasicPidConfig ui; -}; - -#endif // BASICPIDCONFIG_H diff --git a/src/ui/configuration/BasicPidConfig.ui b/src/ui/configuration/BasicPidConfig.ui deleted file mode 100644 index 4be479c989c42bc7f0b61515609a91d1882f61cf..0000000000000000000000000000000000000000 --- a/src/ui/configuration/BasicPidConfig.ui +++ /dev/null @@ -1,32 +0,0 @@ - - - BasicPidConfig - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - 30 - 20 - 141 - 31 - - - - <h2> Basic Pids</h2> - - - - - - diff --git a/src/ui/configuration/BatteryMonitorConfig.cc b/src/ui/configuration/BatteryMonitorConfig.cc deleted file mode 100644 index ec09c817c484a434b2f2cb4bfd10103dd18ebdb8..0000000000000000000000000000000000000000 --- a/src/ui/configuration/BatteryMonitorConfig.cc +++ /dev/null @@ -1,320 +0,0 @@ -#include "BatteryMonitorConfig.h" -#include - -BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - ui.monitorComboBox->addItem(tr("0: Disabled")); - ui.monitorComboBox->addItem(tr("3: Battery Volts")); - ui.monitorComboBox->addItem(tr("4: Voltage and Current")); - - ui.sensorComboBox->addItem(tr("0: Other")); - ui.sensorComboBox->addItem("1: AttoPilot 45A"); - ui.sensorComboBox->addItem("2: AttoPilot 90A"); - ui.sensorComboBox->addItem("3: AttoPilot 180A"); - ui.sensorComboBox->addItem("4: 3DR Power Module"); - - ui.apmVerComboBox->addItem("0: APM1"); - ui.apmVerComboBox->addItem("1: APM2 - 2.5 non 3DR"); - ui.apmVerComboBox->addItem("2: APM2.5 - 3DR Power Module"); - ui.apmVerComboBox->addItem("3: PX4"); - - ui.alertOnLowCheckBox->setVisible(false); //Unimpelemented, but TODO. - - - connect(ui.monitorComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(monitorCurrentIndexChanged(int))); - connect(ui.sensorComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(sensorCurrentIndexChanged(int))); - connect(ui.apmVerComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(apmVerCurrentIndexChanged(int))); - - connect(ui.calcDividerLineEdit,SIGNAL(editingFinished()),this,SLOT(calcDividerSet())); - connect(ui.ampsPerVoltsLineEdit,SIGNAL(editingFinished()),this,SLOT(ampsPerVoltSet())); - connect(ui.battCapacityLineEdit,SIGNAL(editingFinished()),this,SLOT(batteryCapacitySet())); - - - initConnections(); -} -void BatteryMonitorConfig::activeUASSet(UASInterface *uas) -{ - if (m_uas) - { - disconnect(m_uas,SIGNAL(batteryChanged(UASInterface*,double,double,double,int)),this,SLOT(batteryChanged(UASInterface*,double,double,double,int))); - } - AP2ConfigWidget::activeUASSet(uas); - if (!uas) - { - return; - } - connect(uas,SIGNAL(batteryChanged(UASInterface*,double,double,double,int)),this,SLOT(batteryChanged(UASInterface*,double,double,double,int))); - -} -void BatteryMonitorConfig::alertOnLowClicked(bool checked) -{ - Q_UNUSED(checked); -} - -void BatteryMonitorConfig::calcDividerSet() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - bool ok = false; - float newval = ui.calcDividerLineEdit->text().toFloat(&ok); - if (!ok) - { - //Error parsing; - QMessageBox::information(0,"Error","Invalid number entered for voltage divider. Please try again"); - return; - } - m_uas->getParamManager()->setParameter(1,"VOLT_DIVIDER",newval); -} -void BatteryMonitorConfig::ampsPerVoltSet() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - bool ok = false; - float newval = ui.ampsPerVoltsLineEdit->text().toFloat(&ok); - if (!ok) - { - //Error parsing; - QMessageBox::information(0,"Error","Invalid number entered for amps per volts. Please try again"); - return; - } - m_uas->getParamManager()->setParameter(1,"AMPS_PER_VOLT",newval); -} -void BatteryMonitorConfig::batteryCapacitySet() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - bool ok = false; - float newval = ui.battCapacityLineEdit->text().toFloat(&ok); - if (!ok) - { - //Error parsing; - QMessageBox::information(0,"Error","Invalid number entered for amps per volts. Please try again"); - return; - } - m_uas->getParamManager()->setParameter(1,"BATT_CAPACITY",newval); -} - -void BatteryMonitorConfig::monitorCurrentIndexChanged(int index) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (index == 0) //Battery Monitor Disabled - { - m_uas->getParamManager()->setParameter(1,"BATT_VOLT_PIN",-1); - m_uas->getParamManager()->setParameter(1,"BATT_CURR_PIN",-1); - m_uas->getParamManager()->setParameter(1,"BATT_MONITOR",0); - ui.sensorComboBox->setEnabled(false); - ui.apmVerComboBox->setEnabled(false); - ui.measuredVoltsLineEdit->setEnabled(false); - ui.measuredVoltsLineEdit->setEnabled(false); - ui.calcDividerLineEdit->setEnabled(false); - ui.calcVoltsLineEdit->setEnabled(false); - ui.ampsPerVoltsLineEdit->setEnabled(false); - } - else if (index == 1) //Monitor voltage only - { - m_uas->getParamManager()->setParameter(1,"BATT_MONITOR",3); - ui.sensorComboBox->setEnabled(false); - ui.apmVerComboBox->setEnabled(true); - ui.measuredVoltsLineEdit->setEnabled(true); - ui.calcDividerLineEdit->setEnabled(true); - ui.calcVoltsLineEdit->setEnabled(false); - ui.ampsPerVoltsLineEdit->setEnabled(false); - } - else if (index == 2) //Monitor voltage and current - { - m_uas->getParamManager()->setParameter(1,"BATT_MONITOR",4); - ui.sensorComboBox->setEnabled(true); - ui.apmVerComboBox->setEnabled(true); - ui.measuredVoltsLineEdit->setEnabled(true); - ui.calcDividerLineEdit->setEnabled(true); - ui.calcVoltsLineEdit->setEnabled(false); - ui.ampsPerVoltsLineEdit->setEnabled(true); - } - - -} -void BatteryMonitorConfig::sensorCurrentIndexChanged(int index) -{ - float maxvolt = 0.0f; - float maxamps = 0.0f; - float mvpervolt = 0.0f; - float mvperamp = 0.0f; - float topvolt = 0.0f; - float topamps = 0.0f; - - if (index == 1) - { - //atto 45 see https://www.sparkfun.com/products/10643 - maxvolt = 13.6f; - maxamps = 44.7f; - } - else if (index == 2) - { - //atto 90 see https://www.sparkfun.com/products/9028 - maxvolt = 51.8f; - maxamps = 89.4f; - } - else if (index == 3) - { - //atto 180 see https://www.sparkfun.com/products/10644 - maxvolt = 51.8f; - maxamps = 178.8f; - } - else if (index == 4) - { - //3dr - maxvolt = 50.0f; - maxamps = 90.0f; - } - mvpervolt = calculatemVPerVolt(3.3f, maxvolt); - mvperamp = calculatemVPerAmp(3.3f, maxamps); - if (index == 0) - { - //Other - ui.ampsPerVoltsLineEdit->setEnabled(true); - ui.calcDividerLineEdit->setEnabled(true); - ui.measuredVoltsLineEdit->setEnabled(true); - } - else - { - topvolt = (maxvolt * mvpervolt) / 1000.0; - topamps = (maxamps * mvperamp) / 1000.0; - - ui.calcDividerLineEdit->setText(QString::number(maxvolt/topvolt)); - ui.ampsPerVoltsLineEdit->setText(QString::number(maxamps / topamps)); - ui.ampsPerVoltsLineEdit->setEnabled(false); - ui.calcDividerLineEdit->setEnabled(false); - ui.measuredVoltsLineEdit->setEnabled(false); - } -} -float BatteryMonitorConfig::calculatemVPerAmp(float maxvoltsout,float maxamps) -{ - return (1000.0 * (maxvoltsout/maxamps)); -} - -float BatteryMonitorConfig::calculatemVPerVolt(float maxvoltsout,float maxvolts) -{ - return (1000.0 * (maxvoltsout/maxvolts)); -} - -void BatteryMonitorConfig::apmVerCurrentIndexChanged(int index) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (index == 0) //APM1 - { - m_uas->getParamManager()->setParameter(1,"BATT_VOLT_PIN",0); - m_uas->getParamManager()->setParameter(1,"BATT_CURR_PIN",1); - } - else if (index == 1) //APM2 - { - m_uas->getParamManager()->setParameter(1,"BATT_VOLT_PIN",1); - m_uas->getParamManager()->setParameter(1,"BATT_CURR_PIN",2); - } - else if (index == 2) //APM2.5 - { - m_uas->getParamManager()->setParameter(1,"BATT_VOLT_PIN",13); - m_uas->getParamManager()->setParameter(1,"BATT_CURR_PIN",12); - } - else if (index == 3) //PX4 - { - m_uas->getParamManager()->setParameter(1,"BATT_VOLT_PIN",100); - m_uas->getParamManager()->setParameter(1,"BATT_CURR_PIN",101); - m_uas->getParamManager()->setParameter(1,"VOLT_DIVIDER",1); - ui.calcDividerLineEdit->setText("1"); - } -} - -BatteryMonitorConfig::~BatteryMonitorConfig() -{ -} -void BatteryMonitorConfig::batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds) -{ - Q_UNUSED(uas); - Q_UNUSED(current); - Q_UNUSED(percent); - Q_UNUSED(seconds); - - ui.calcVoltsLineEdit->setText(QString::number(voltage,'f',2)); - if (ui.measuredVoltsLineEdit->text() == "") - { - ui.measuredVoltsLineEdit->setText(ui.calcVoltsLineEdit->text()); - } -} - -void BatteryMonitorConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "VOLT_DIVIDER") - { - ui.calcDividerLineEdit->setText(QString::number(value.toFloat(),'f',4)); - } - else if (parameterName == "AMP_PER_VOLT") - { - ui.ampsPerVoltsLineEdit->setText(QString::number(value.toFloat(),'g',2)); - - } - else if (parameterName == "BATT_MONITOR") - { - if (value.toInt() == 0) //0: Disable - { - ui.monitorComboBox->setCurrentIndex(0); - } - else if (value.toInt() == 3) //3: Battery volts - { - ui.monitorComboBox->setCurrentIndex(1); - } - else if (value.toInt() == 4) //4: Voltage and Current - { - ui.monitorComboBox->setCurrentIndex(2); - } - - } - else if (parameterName == "BATT_CAPACITY") - { - ui.battCapacityLineEdit->setText(QString::number(value.toFloat())); - } - else if (parameterName == "BATT_VOLT_PIN") - { - int ivalue = value.toInt(); - if (ivalue == 0) //APM1 - { - ui.apmVerComboBox->setCurrentIndex(0); - } - else if (ivalue == 1) //APM2 - { - ui.apmVerComboBox->setCurrentIndex(1); - } - else if (ivalue == 13) //APM2.5 - { - ui.apmVerComboBox->setCurrentIndex(2); - } - else if (ivalue == 100) //PX4 - { - ui.apmVerComboBox->setCurrentIndex(3); - } - } - else if (parameterName == "BATT_CURR_PIN") - { - //Unused at the moment, everything is off BATT_VOLT_PIN - } -} diff --git a/src/ui/configuration/BatteryMonitorConfig.h b/src/ui/configuration/BatteryMonitorConfig.h deleted file mode 100644 index 417e6922a95e8fe73e71f1041c0a9865ac3bb182..0000000000000000000000000000000000000000 --- a/src/ui/configuration/BatteryMonitorConfig.h +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef BATTERYMONITORCONFIG_H -#define BATTERYMONITORCONFIG_H - -#include -#include "AP2ConfigWidget.h" -#include "ui_BatteryMonitorConfig.h" - -class BatteryMonitorConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit BatteryMonitorConfig(QWidget *parent = 0); - ~BatteryMonitorConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void monitorCurrentIndexChanged(int index); - void sensorCurrentIndexChanged(int index); - void apmVerCurrentIndexChanged(int index); - void calcDividerSet(); - void ampsPerVoltSet(); - void batteryCapacitySet(); - void alertOnLowClicked(bool checked); - void activeUASSet(UASInterface *uas); - void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds); -private: - Ui::BatteryMonitorConfig ui; - inline float calculatemVPerAmp(float maxvoltsout,float maxamps); - inline float calculatemVPerVolt(float maxvoltsout,float maxvolts); -}; - -#endif // BATTERYMONITORCONFIG_H diff --git a/src/ui/configuration/BatteryMonitorConfig.ui b/src/ui/configuration/BatteryMonitorConfig.ui deleted file mode 100644 index 5d11f960adc90b000a3ff7e3c50c464a039c6644..0000000000000000000000000000000000000000 --- a/src/ui/configuration/BatteryMonitorConfig.ui +++ /dev/null @@ -1,231 +0,0 @@ - - - BatteryMonitorConfig - - - - 0 - 0 - 745 - 494 - - - - Form - - - - - 20 - 20 - 141 - 31 - - - - <h2>Battery Monitor</h2> - - - false - - - - - - 10 - 70 - 141 - 51 - - - - - - - :/files/images/devices/BR-APMPWRDEAN-2.jpg - - - true - - - - - - 480 - 120 - 91 - 17 - - - - Alert On Low - - - - - - 160 - 170 - 241 - 141 - - - - Calibration - - - - - - - - - - 1. Measured battery voltage: - - - - - - - 2. Battery voltage (Calc'ed): - - - - - - - 3. Voltage divider (Calc'ed): - - - - - - - 4. Amperes per volt: - - - - - - - - - - - false - - - - - - - false - - - - - - - false - - - - - - - false - - - - - - - - - - - - - 160 - 70 - 281 - 91 - - - - - - - - - Monitor - - - - - - - Sensor - - - - - - - APM Version - - - - - - - - - - - - - - - - - - - - - - - - 470 - 70 - 195 - 41 - - - - - - - Battery Capacity: - - - - - - - - - - mAh - - - - - - - - - - - diff --git a/src/ui/configuration/CameraGimbalConfig.cc b/src/ui/configuration/CameraGimbalConfig.cc deleted file mode 100644 index 7d4317e48a1c56fa785d950254fad69c75576bc7..0000000000000000000000000000000000000000 --- a/src/ui/configuration/CameraGimbalConfig.cc +++ /dev/null @@ -1,669 +0,0 @@ -#include -#include - -#include "CameraGimbalConfig.h" - -CameraGimbalConfig::CameraGimbalConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - ui.tiltChannelComboBox->addItem(tr("Disable")); - ui.tiltChannelComboBox->addItem("RC5"); - ui.tiltChannelComboBox->addItem("RC6"); - ui.tiltChannelComboBox->addItem("RC7"); - ui.tiltChannelComboBox->addItem("RC8"); - ui.tiltChannelComboBox->addItem("RC10"); - ui.tiltChannelComboBox->addItem("RC11"); - - ui.tiltInputChannelComboBox->addItem(tr("Disable")); - ui.tiltInputChannelComboBox->addItem("RC5"); - ui.tiltInputChannelComboBox->addItem("RC6"); - ui.tiltInputChannelComboBox->addItem("RC7"); - ui.tiltInputChannelComboBox->addItem("RC8"); - - ui.rollChannelComboBox->addItem(tr("Disable")); - ui.rollChannelComboBox->addItem("RC5"); - ui.rollChannelComboBox->addItem("RC6"); - ui.rollChannelComboBox->addItem("RC7"); - ui.rollChannelComboBox->addItem("RC8"); - ui.rollChannelComboBox->addItem("RC10"); - ui.rollChannelComboBox->addItem("RC11"); - - ui.rollInputChannelComboBox->addItem(tr("Disable")); - ui.rollInputChannelComboBox->addItem("RC5"); - ui.rollInputChannelComboBox->addItem("RC6"); - ui.rollInputChannelComboBox->addItem("RC7"); - ui.rollInputChannelComboBox->addItem("RC8"); - - - ui.panChannelComboBox->addItem(tr("Disable")); - ui.panChannelComboBox->addItem("RC5"); - ui.panChannelComboBox->addItem("RC6"); - ui.panChannelComboBox->addItem("RC7"); - ui.panChannelComboBox->addItem("RC8"); - ui.panChannelComboBox->addItem("RC10"); - ui.panChannelComboBox->addItem("RC11"); - - ui.panInputChannelComboBox->addItem(tr("Disable")); - ui.panInputChannelComboBox->addItem("RC5"); - ui.panInputChannelComboBox->addItem("RC6"); - ui.panInputChannelComboBox->addItem("RC7"); - ui.panInputChannelComboBox->addItem("RC8"); - - - ui.shutterChannelComboBox->addItem(tr("Disable")); - ui.shutterChannelComboBox->addItem(tr("Relay")); - ui.shutterChannelComboBox->addItem(tr("Transistor")); - ui.shutterChannelComboBox->addItem("RC5"); - ui.shutterChannelComboBox->addItem("RC6"); - ui.shutterChannelComboBox->addItem("RC7"); - ui.shutterChannelComboBox->addItem("RC8"); - ui.shutterChannelComboBox->addItem("RC10"); - ui.shutterChannelComboBox->addItem("RC11"); - - connect(ui.tiltServoMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updateTilt())); - connect(ui.tiltServoMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updateTilt())); - connect(ui.tiltAngleMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updateTilt())); - connect(ui.tiltAngleMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updateTilt())); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - connect(ui.tiltInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - connect(ui.tiltReverseCheckBox,SIGNAL(clicked(bool)),this,SLOT(updateTilt())); - connect(ui.tiltStabilizeCheckBox,SIGNAL(clicked(bool)),this,SLOT(updateTilt())); - - connect(ui.rollServoMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRoll())); - connect(ui.rollServoMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRoll())); - connect(ui.rollAngleMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRoll())); - connect(ui.rollAngleMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRoll())); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - connect(ui.rollInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - connect(ui.rollReverseCheckBox,SIGNAL(clicked(bool)),this,SLOT(updateRoll())); - connect(ui.rollStabilizeCheckBox,SIGNAL(clicked(bool)),this,SLOT(updateRoll())); - - connect(ui.panServoMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updatePan())); - connect(ui.panServoMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updatePan())); - connect(ui.panAngleMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updatePan())); - connect(ui.panAngleMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updatePan())); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - connect(ui.panInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - connect(ui.panReverseCheckBox,SIGNAL(clicked(bool)),this,SLOT(updatePan())); - connect(ui.panStabilizeCheckBox,SIGNAL(clicked(bool)),this,SLOT(updatePan())); - - - connect(ui.shutterServoMinSpinBox,SIGNAL(editingFinished()),this,SLOT(updateShutter())); - connect(ui.shutterServoMaxSpinBox,SIGNAL(editingFinished()),this,SLOT(updateShutter())); - connect(ui.shutterPushedSpinBox,SIGNAL(editingFinished()),this,SLOT(updateShutter())); - connect(ui.shutterNotPushedSpinBox,SIGNAL(editingFinished()),this,SLOT(updateShutter())); - connect(ui.shutterDurationSpinBox,SIGNAL(editingFinished()),this,SLOT(updateShutter())); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - - connect(ui.retractXSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRetractAngles())); - connect(ui.retractYSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRetractAngles())); - connect(ui.retractZSpinBox,SIGNAL(editingFinished()),this,SLOT(updateRetractAngles())); - - connect(ui.controlXSpinBox,SIGNAL(editingFinished()),this,SLOT(updateControlAngles())); - connect(ui.controlYSpinBox,SIGNAL(editingFinished()),this,SLOT(updateControlAngles())); - connect(ui.controlZSpinBox,SIGNAL(editingFinished()),this,SLOT(updateControlAngles())); - - connect(ui.neutralXSpinBox,SIGNAL(editingFinished()),this,SLOT(updateNeutralAngles())); - connect(ui.neutralYSpinBox,SIGNAL(editingFinished()),this,SLOT(updateNeutralAngles())); - connect(ui.neutralZSpinBox,SIGNAL(editingFinished()),this,SLOT(updateNeutralAngles())); - initConnections(); - -} -void CameraGimbalConfig::updateRetractAngles() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"MNT_RETRACT_X",ui.retractXSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_RETRACT_Y",ui.retractYSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_RETRACT_Z",ui.retractZSpinBox->value()); -} - -void CameraGimbalConfig::updateNeutralAngles() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"MNT_NEUTRAL_X",ui.neutralXSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_NEUTRAL_Y",ui.neutralYSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_NEUTRAL_Z",ui.neutralZSpinBox->value()); -} - -void CameraGimbalConfig::updateControlAngles() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"MNT_CONTROL_X",ui.controlXSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_CONTROL_Y",ui.controlYSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_CONTROL_Z",ui.controlZSpinBox->value()); -} - -void CameraGimbalConfig::updateTilt() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (!m_tiltPrefix.isEmpty()) - { - //We need to set this to 0 for disabled. - m_uas->getParamManager()->setParameter(1,m_tiltPrefix + "FUNCTION",0); - } - if (ui.tiltChannelComboBox->currentIndex() == 0) - { - //Disabled - return; - } - - m_uas->getParamManager()->setParameter(1,ui.tiltChannelComboBox->currentText() + "_FUNCTION",7); - m_uas->getParamManager()->setParameter(1,ui.tiltChannelComboBox->currentText() + "_MIN",ui.tiltServoMinSpinBox->value()); - m_uas->getParamManager()->setParameter(1,ui.tiltChannelComboBox->currentText() + "_MAX",ui.tiltServoMaxSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_ANGMIN_TIL",ui.tiltAngleMinSpinBox->value() * 100); - m_uas->getParamManager()->setParameter(1,"MNT_ANGMAX_TIL",ui.tiltAngleMaxSpinBox->value() * 100); - m_uas->getParamManager()->setParameter(1,ui.tiltChannelComboBox->currentText() + "_REV",(ui.tiltReverseCheckBox->isChecked() ? 1 : 0)); - if (ui.tiltInputChannelComboBox->currentIndex() == 0) - { - m_uas->getParamManager()->setParameter(1,"MNT_RC_IN_TILT",0); - } - else - { - m_uas->getParamManager()->setParameter(1,"MNT_RC_IN_TILT",ui.tiltInputChannelComboBox->currentIndex()+4); - } -} - -void CameraGimbalConfig::updateRoll() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,ui.rollChannelComboBox->currentText() + "_FUNCTION",8); - m_uas->getParamManager()->setParameter(1,ui.rollChannelComboBox->currentText() + "_MIN",ui.rollServoMinSpinBox->value()); - m_uas->getParamManager()->setParameter(1,ui.rollChannelComboBox->currentText() + "_MAX",ui.rollServoMaxSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_ANGMIN_ROL",ui.rollAngleMinSpinBox->value() * 100); - m_uas->getParamManager()->setParameter(1,"MNT_ANGMAX_ROL",ui.rollAngleMaxSpinBox->value() * 100); - m_uas->getParamManager()->setParameter(1,ui.rollChannelComboBox->currentText() + "_REV",(ui.rollReverseCheckBox->isChecked() ? 1 : 0)); - if (ui.rollInputChannelComboBox->currentIndex() == 0) - { - m_uas->getParamManager()->setParameter(1,"MNT_RC_IN_ROLL",0); - } - else - { - m_uas->getParamManager()->setParameter(1,"MNT_RC_IN_ROLL",ui.rollInputChannelComboBox->currentIndex()+4); - } -} - -void CameraGimbalConfig::updatePan() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,ui.panChannelComboBox->currentText() + "_FUNCTION",6); - m_uas->getParamManager()->setParameter(1,ui.panChannelComboBox->currentText() + "_MIN",ui.panServoMinSpinBox->value()); - m_uas->getParamManager()->setParameter(1,ui.panChannelComboBox->currentText() + "_MAX",ui.panServoMaxSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"MNT_ANGMIN_PAN",ui.panAngleMinSpinBox->value() * 100); - m_uas->getParamManager()->setParameter(1,"MNT_ANGMAX_PAN",ui.panAngleMaxSpinBox->value() * 100); - m_uas->getParamManager()->setParameter(1,ui.panChannelComboBox->currentText() + "_REV",(ui.panReverseCheckBox->isChecked() ? 1 : 0)); - if (ui.panInputChannelComboBox->currentIndex() == 0) - { - m_uas->getParamManager()->setParameter(1,"MNT_RC_IN_PAN",0); - } - else - { - m_uas->getParamManager()->setParameter(1,"MNT_RC_IN_PAN",ui.panInputChannelComboBox->currentIndex()+4); - } -} - -void CameraGimbalConfig::updateShutter() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (ui.shutterChannelComboBox->currentIndex() == 0) //Disabled - { - m_uas->getParamManager()->setParameter(1,"CAM_TRIGG_TYPE",0); - } - else if (ui.shutterChannelComboBox->currentIndex() == 1) //Relay - { - m_uas->getParamManager()->setParameter(1,"CAM_TRIGG_TYPE",1); - } - else if (ui.shutterChannelComboBox->currentIndex() == 2) //Transistor - { - m_uas->getParamManager()->setParameter(1,"CAM_TRIGG_TYPE",4); - } - else - { - m_uas->getParamManager()->setParameter(1,ui.shutterChannelComboBox->currentText() + "_FUNCTION",10); - m_uas->getParamManager()->setParameter(1,"CAM_TRIGG_TYPE",0); - } - m_uas->getParamManager()->setParameter(1,ui.shutterChannelComboBox->currentText() + "_MIN",ui.shutterServoMinSpinBox->value()); - m_uas->getParamManager()->setParameter(1,ui.shutterChannelComboBox->currentText() + "_MAX",ui.shutterServoMaxSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"CAM_SERVO_ON",ui.shutterPushedSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"CAM_SERVO_OFF",ui.shutterNotPushedSpinBox->value()); - m_uas->getParamManager()->setParameter(1,"CAM_DURATION",ui.shutterDurationSpinBox->value()); - - -} - - -CameraGimbalConfig::~CameraGimbalConfig() -{ -} - -void CameraGimbalConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "MNT_ANGMIN_TIL") //TILT - { - ui.tiltAngleMinSpinBox->setValue(value.toInt() / 100.0); - } - else if (parameterName == "MNT_ANGMAX_TIL") - { - ui.tiltAngleMaxSpinBox->setValue(value.toInt() / 100.0); - } - else if (parameterName == "MNT_RC_IN_TILT") - { - disconnect(ui.tiltInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - if (value.toInt() == 0) - { - ui.tiltInputChannelComboBox->setCurrentIndex(0); - } - else - { - ui.tiltInputChannelComboBox->setCurrentIndex(value.toInt()-4); - } - connect(ui.tiltInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - } - else if (parameterName == "MNT_ANGMIN_ROL") //ROLL - { - ui.rollAngleMinSpinBox->setValue(value.toInt() / 100.0); - } - else if (parameterName == "MNT_ANGMAX_ROL") - { - ui.rollAngleMaxSpinBox->setValue(value.toInt() / 100.0); - } - else if (parameterName == "MNT_RC_IN_ROLL") - { - disconnect(ui.rollInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - if (value.toInt() == 0) - { - ui.rollInputChannelComboBox->setCurrentIndex(0); - } - else - { - ui.rollInputChannelComboBox->setCurrentIndex(value.toInt()-4); - } - connect(ui.rollInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - } - else if (parameterName == "MNT_ANGMIN_PAN") //PAN - { - ui.panAngleMinSpinBox->setValue(value.toInt() / 100.0); - } - else if (parameterName == "MNT_ANGMAX_PAN") - { - ui.panAngleMaxSpinBox->setValue(value.toInt() / 100.0); - } - else if (parameterName == "MNT_RC_IN_PAN") - { - disconnect(ui.panInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - if (value.toInt() == 0) - { - ui.panInputChannelComboBox->setCurrentIndex(0); - } - else - { - ui.panInputChannelComboBox->setCurrentIndex(value.toInt()-4); - } - connect(ui.panInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - } - if (parameterName == "CAM_DURATION") - { - ui.shutterDurationSpinBox->setValue(value.toInt()); - } - else if (parameterName == "CAM_SERVO_OFF") - { - ui.shutterNotPushedSpinBox->setValue(value.toInt()); - } - else if (parameterName == "CAM_SERVO_ON") - { - ui.shutterPushedSpinBox->setValue(value.toInt()); - } - else if (parameterName == "CAM_TRIGG_TYPE") - { - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - if (value.toInt() == 0) //Disabled - { - ui.shutterChannelComboBox->setCurrentIndex(0); - ///TODO: Request all _FUNCTIONs here to find out if shutter is actually disabled. - } - else if (value.toInt() == 1) // Relay - { - ui.shutterChannelComboBox->setCurrentIndex(1); - } - else if (value.toInt() == 4) //Transistor - { - ui.shutterChannelComboBox->setCurrentIndex(2); - } - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - } - if (parameterName.startsWith(m_shutterPrefix) && !m_shutterPrefix.isEmpty()) - { - if (parameterName.endsWith("MIN")) - { - ui.shutterServoMinSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("MAX")) - { - ui.shutterServoMaxSpinBox->setValue(value.toInt()); - } - } - else if (parameterName.startsWith(m_tiltPrefix) && !m_tiltPrefix.isEmpty()) - { - if (parameterName.endsWith("MIN")) - { - ui.tiltServoMinSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("MAX")) - { - ui.tiltServoMaxSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("REV")) - { - if (value.toInt() == 0) - { - ui.tiltReverseCheckBox->setChecked(false); - } - else - { - ui.tiltReverseCheckBox->setChecked(true); - } - } - } - else if (parameterName.startsWith(m_rollPrefix) && !m_rollPrefix.isEmpty()) - { - if (parameterName.endsWith("MIN")) - { - ui.rollServoMinSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("MAX")) - { - ui.rollServoMaxSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("REV")) - { - if (value.toInt() == 0) - { - ui.rollReverseCheckBox->setChecked(false); - } - else - { - ui.rollReverseCheckBox->setChecked(true); - } - } - } - else if (parameterName.startsWith(m_panPrefix) && !m_panPrefix.isEmpty()) - { - if (parameterName.endsWith("MIN")) - { - ui.panServoMinSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("MAX")) - { - ui.panServoMaxSpinBox->setValue(value.toInt()); - } - else if (parameterName.endsWith("REV")) - { - if (value.toInt() == 0) - { - ui.panReverseCheckBox->setChecked(false); - } - else - { - ui.panReverseCheckBox->setChecked(true); - } - } - } - else if (parameterName == "RC5_FUNCTION") - { - if (value.toInt() == 10) - { - //RC5 is shutter. - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - ui.shutterChannelComboBox->setCurrentIndex(3); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - m_shutterPrefix = "RC5_"; - } - else if (value.toInt() == 8) - { - //RC5 is roll - disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - ui.rollChannelComboBox->setCurrentIndex(1); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - m_rollPrefix = "RC5_"; - } - else if (value.toInt() == 7) - { - //RC5 is tilt - disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - ui.tiltChannelComboBox->setCurrentIndex(1); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - m_tiltPrefix = "RC5_"; - } - else if (value.toInt() == 6) - { - //RC5 is pan - disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - ui.panChannelComboBox->setCurrentIndex(1); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - m_panPrefix = "RC5_"; - } - m_uas->getParamManager()->requestParameterUpdate(1,"RC5_MIN"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC5_MAX"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC5_REV"); - } - else if (parameterName == "RC6_FUNCTION") - { - if (value.toInt() == 10) - { - //RC6 is shutter. - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - ui.shutterChannelComboBox->setCurrentIndex(4); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - m_shutterPrefix = "RC6_"; - } - else if (value.toInt() == 8) - { - //RC6 is roll - disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - ui.rollChannelComboBox->setCurrentIndex(2); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - m_rollPrefix = "RC6_"; - } - else if (value.toInt() == 7) - { - //RC6 is tilt - disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - ui.tiltChannelComboBox->setCurrentIndex(2); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - m_tiltPrefix = "RC6_"; - } - else if (value.toInt() == 6) - { - //RC6 is pan - disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - ui.panChannelComboBox->setCurrentIndex(2); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - m_panPrefix = "RC6_"; - } - m_uas->getParamManager()->requestParameterUpdate(1,"RC6_MIN"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC6_MAX"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC6_REV"); - } - else if (parameterName == "RC7_FUNCTION") - { - if (value.toInt() == 10) - { - //RC7 is shutter. - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - ui.shutterChannelComboBox->setCurrentIndex(5); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - m_shutterPrefix = "RC7_"; - } - else if (value.toInt() == 8) - { - //RC7 is roll - disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - ui.rollChannelComboBox->setCurrentIndex(3); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - m_rollPrefix = "RC7_"; - } - else if (value.toInt() == 7) - { - //RC7 is tilt - disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - ui.tiltChannelComboBox->setCurrentIndex(3); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - m_tiltPrefix = "RC7_"; - } - else if (value.toInt() == 6) - { - //RC7 is pan - disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - ui.panChannelComboBox->setCurrentIndex(3); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - m_panPrefix = "RC7_"; - } - m_uas->getParamManager()->requestParameterUpdate(1,"RC7_MIN"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC7_MAX"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC7_REV"); - } - else if (parameterName == "RC8_FUNCTION") - { - if (value.toInt() == 10) - { - //RC8 is shutter. - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - ui.shutterChannelComboBox->setCurrentIndex(6); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - m_shutterPrefix = "RC8_"; - } - else if (value.toInt() == 8) - { - //RC8 is roll - disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - ui.rollChannelComboBox->setCurrentIndex(4); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - m_rollPrefix = "RC8_"; - } - else if (value.toInt() == 7) - { - //RC8 is tilt - disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - ui.tiltChannelComboBox->setCurrentIndex(4); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - m_tiltPrefix = "RC8_"; - } - else if (value.toInt() == 6) - { - //RC8 is pan - disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - ui.panChannelComboBox->setCurrentIndex(4); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - m_panPrefix = "RC8_"; - } - m_uas->getParamManager()->requestParameterUpdate(1,"RC8_MIN"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC8_MAX"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC8_REV"); - } - else if (parameterName == "RC10_FUNCTION") - { - if (value.toInt() == 10) - { - //RC10 is shutter. - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - ui.shutterChannelComboBox->setCurrentIndex(7); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - m_shutterPrefix = "RC10_"; - } - else if (value.toInt() == 8) - { - //RC10 is roll - disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - ui.rollChannelComboBox->setCurrentIndex(5); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - m_rollPrefix = "RC10_"; - } - else if (value.toInt() == 7) - { - //RC10 is tilt - disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - ui.tiltChannelComboBox->setCurrentIndex(5); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - m_tiltPrefix = "RC10_"; - } - else if (value.toInt() == 6) - { - //RC10 is pan - disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - ui.panChannelComboBox->setCurrentIndex(5); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - m_panPrefix = "RC10_"; - } - m_uas->getParamManager()->requestParameterUpdate(1,"RC10_MIN"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC10_MAX"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC10_REV"); - } - else if (parameterName == "RC11_FUNCTION") - { - if (value.toInt() == 10) - { - //RC11 is shutter. - disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - ui.shutterChannelComboBox->setCurrentIndex(8); - connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter())); - m_shutterPrefix = "RC11_"; - } - else if (value.toInt() == 8) - { - //RC11 is roll - disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - ui.rollChannelComboBox->setCurrentIndex(6); - connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll())); - m_rollPrefix = "RC11_"; - } - else if (value.toInt() == 7) - { - //RC11 is tilt - disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - ui.tiltChannelComboBox->setCurrentIndex(6); - connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt())); - m_tiltPrefix = "RC11_"; - } - else if (value.toInt() == 6) - { - //RC11 is pan - disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - ui.panChannelComboBox->setCurrentIndex(6); - connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan())); - m_panPrefix = "RC11_"; - } - m_uas->getParamManager()->requestParameterUpdate(1,"RC11_MIN"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC11_MAX"); - m_uas->getParamManager()->requestParameterUpdate(1,"RC11_REV"); - } -} diff --git a/src/ui/configuration/CameraGimbalConfig.h b/src/ui/configuration/CameraGimbalConfig.h deleted file mode 100644 index 9f686243f707e689ee25dcfa390598cd81527d94..0000000000000000000000000000000000000000 --- a/src/ui/configuration/CameraGimbalConfig.h +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef CAMERAGIMBALCONFIG_H -#define CAMERAGIMBALCONFIG_H - -#include -#include "AP2ConfigWidget.h" -#include "ui_CameraGimbalConfig.h" - -class CameraGimbalConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit CameraGimbalConfig(QWidget *parent = 0); - ~CameraGimbalConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void updateTilt(); - void updateRoll(); - void updatePan(); - void updateShutter(); - void updateRetractAngles(); - void updateNeutralAngles(); - void updateControlAngles(); -private: - Ui::CameraGimbalConfig ui; - QString m_shutterPrefix; - QString m_rollPrefix; - QString m_tiltPrefix; - QString m_panPrefix; -}; - -#endif // CAMERAGIMBALCONFIG_H diff --git a/src/ui/configuration/CameraGimbalConfig.ui b/src/ui/configuration/CameraGimbalConfig.ui deleted file mode 100644 index 1775b5945e38bc7c009e59443088c3b129ba6592..0000000000000000000000000000000000000000 --- a/src/ui/configuration/CameraGimbalConfig.ui +++ /dev/null @@ -1,965 +0,0 @@ - - - CameraGimbalConfig - - - - 0 - 0 - 959 - 813 - - - - Form - - - - - 30 - 20 - 131 - 31 - - - - <h2>Camera Gimbal</h2> - - - false - - - - - - 30 - 60 - 541 - 151 - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <h3>Input Ch</h3> - - - - - - - Reverse - - - - - - - <h3>Angle Limits</h3> - - - - - - - <h3>Servo Limits</h3> - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - <h2>Tilt</h2> - - - Qt::AlignCenter - - - - - - - Stabilize Tilt - - - - - - - - 250 - 120 - - - - - 250 - 120 - - - - - - - :/files/images/devices/cameraGimalPitch1.png - - - true - - - - - - - 3000 - - - 1000 - - - - - - - 3000 - - - 2000 - - - - - - - -100 - - - 100 - - - 100 - - - - - - - 100 - - - 0 - - - - - - - - - - - - 30 - 230 - 541 - 149 - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - <h3>Input Ch</h3> - - - - - - - Reverse - - - - - - - <h3>Angle Limits</h3> - - - - - - - <h3>Servo Limits</h3> - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - <h2>Roll</h2> - - - Qt::AlignCenter - - - - - - - Stabilize Roll - - - - - - - - 250 - 120 - - - - - 250 - 120 - - - - - - - :/files/images/devices/cameraGimalRoll1.png - - - true - - - - - - - 3000 - - - 1000 - - - - - - - 3000 - - - 2000 - - - - - - - -100 - - - 100 - - - 100 - - - - - - - -100 - - - 100 - - - 100 - - - - - - - - - 30 - 390 - 541 - 149 - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - <h3>Input Ch</h3> - - - - - - - Reverse - - - - - - - <h3>Angle Limits</h3> - - - - - - - <h3>Servo Limits</h3> - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - <h2>Pan</h2> - - - Qt::AlignCenter - - - - - - - Stabilize Pan - - - - - - - - 250 - 120 - - - - - 250 - 120 - - - - - - - :/files/images/devices/cameraGimalYaw.png - - - true - - - - - - - 3000 - - - 1000 - - - - - - - -100 - - - 100 - - - 100 - - - - - - - -100 - - - 100 - - - 100 - - - - - - - 3000 - - - 2000 - - - - - - - - - 30 - 550 - 541 - 181 - - - - - - - - 250 - 120 - - - - - 250 - 120 - - - - - - - :/files/images/devices/Shutter.png - - - true - - - - - - - Duration -(1/10th sec) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Pushed - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Not Pushed - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <h3>Shutter</h3> - - - - - - - <h3>Servo Limits</h3> - - - - - - - Max - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Min - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - <h2>Shutter</h2> - - - Qt::AlignCenter - - - - - - - <h2>Please set the Ch7 Option to Camera Trigger</h2> - - - Qt::AlignCenter - - - - - - - 3000 - - - 1000 - - - - - - - 3000 - - - 2000 - - - - - - - 100 - - - 20 - - - - - - - 3000 - - - 1000 - - - - - - - 3000 - - - 2000 - - - - - - - - - 590 - 60 - 171 - 131 - - - - Retract Angles - - - - - - - - - - X - - - - - - - Y - - - - - - - Z - - - - - - - - - - - -180 - - - 180 - - - - - - - -180 - - - 180 - - - - - - - -180 - - - 180 - - - - - - - - - - - - - 590 - 210 - 171 - 131 - - - - Neutral Angles - - - - - - - - - - X - - - - - - - Y - - - - - - - Z - - - - - - - - - - - -180 - - - 180 - - - - - - - -180 - - - 180 - - - - - - - -180 - - - 180 - - - - - - - - - - - - - 590 - 360 - 171 - 131 - - - - Control Angles - - - - - - - - - - X - - - - - - - Y - - - - - - - Z - - - - - - - - - - - -180 - - - 180 - - - - - - - -180 - - - 180 - - - - - - - -180 - - - 180 - - - - - - - - - - - - - - - diff --git a/src/ui/configuration/CompassConfig.cc b/src/ui/configuration/CompassConfig.cc deleted file mode 100644 index 411cf79b6901211a1044ff18ba92c43952ffc129..0000000000000000000000000000000000000000 --- a/src/ui/configuration/CompassConfig.cc +++ /dev/null @@ -1,139 +0,0 @@ -#include "CompassConfig.h" - - -CompassConfig::CompassConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - ui.autoDecCheckBox->setEnabled(false); - ui.enableCheckBox->setEnabled(false); - ui.orientationComboBox->setEnabled(false); - ui.declinationLineEdit->setEnabled(false); - connect(ui.enableCheckBox,SIGNAL(clicked(bool)),this,SLOT(enableClicked(bool))); - connect(ui.autoDecCheckBox,SIGNAL(clicked(bool)),this,SLOT(autoDecClicked(bool))); - connect(ui.orientationComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(orientationComboChanged(int))); - - ui.orientationComboBox->addItem("ROTATION_NONE"); - ui.orientationComboBox->addItem("ROTATION_YAW_45"); - ui.orientationComboBox->addItem("ROTATION_YAW_90"); - ui.orientationComboBox->addItem("ROTATION_YAW_135"); - ui.orientationComboBox->addItem("ROTATION_YAW_180"); - ui.orientationComboBox->addItem("ROTATION_YAW_225"); - ui.orientationComboBox->addItem("ROTATION_YAW_270"); - ui.orientationComboBox->addItem("ROTATION_YAW_315"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_45"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_90"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_135"); - ui.orientationComboBox->addItem("ROTATION_PITCH_180"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_225"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_270"); - ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_315"); - ui.orientationComboBox->addItem("ROTATION_ROLL_90"); - ui.orientationComboBox->addItem("ROTATION_ROLL_90_YAW_45"); - ui.orientationComboBox->addItem("ROTATION_ROLL_90_YAW_90"); - ui.orientationComboBox->addItem("ROTATION_ROLL_90_YAW_135"); - ui.orientationComboBox->addItem("ROTATION_ROLL_270"); - ui.orientationComboBox->addItem("ROTATION_ROLL_270_YAW_45"); - ui.orientationComboBox->addItem("ROTATION_ROLL_270_YAW_90"); - ui.orientationComboBox->addItem("ROTATION_ROLL_270_YAW_135"); - ui.orientationComboBox->addItem("ROTATION_PITCH_90"); - ui.orientationComboBox->addItem("ROTATION_PITCH_270"); - ui.orientationComboBox->addItem("ROTATION_MAX"); - initConnections(); -} -CompassConfig::~CompassConfig() -{ -} -void CompassConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "MAG_ENABLE") - { - if (value.toInt() == 0) - { - ui.enableCheckBox->setChecked(false); - ui.autoDecCheckBox->setEnabled(false); - ui.declinationLineEdit->setEnabled(false); - ui.orientationComboBox->setEnabled(false); - } - else - { - ui.enableCheckBox->setChecked(true); - ui.autoDecCheckBox->setEnabled(true); - ui.declinationLineEdit->setEnabled(true); - ui.orientationComboBox->setEnabled(true); - } - ui.enableCheckBox->setEnabled(true); - } - else if (parameterName == "COMPASS_AUTODEC") - { - if (value.toInt() == 0) - { - ui.autoDecCheckBox->setChecked(false); - } - else - { - ui.autoDecCheckBox->setChecked(true); - } - } - else if (parameterName == "COMPASS_DEC") - { - ui.declinationLineEdit->setText(QString::number(value.toDouble())); - } - else if (parameterName == "COMPASS_ORIENT") - { - disconnect(ui.orientationComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(orientationComboChanged(int))); - ui.orientationComboBox->setCurrentIndex(value.toInt()); - connect(ui.orientationComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(orientationComboChanged(int))); - } -} - -void CompassConfig::enableClicked(bool enabled) -{ - if (m_uas) - { - if (enabled) - { - m_uas->getParamManager()->setParameter(1,"MAG_ENABLE",QVariant(1)); - ui.autoDecCheckBox->setEnabled(true); - if (!ui.autoDecCheckBox->isChecked()) - { - ui.declinationLineEdit->setEnabled(true); - } - } - else - { - m_uas->getParamManager()->setParameter(1,"MAG_ENABLE",QVariant(0)); - ui.autoDecCheckBox->setEnabled(false); - ui.declinationLineEdit->setEnabled(false); - } - } -} - -void CompassConfig::autoDecClicked(bool enabled) -{ - if (m_uas) - { - if (enabled) - { - m_uas->getParamManager()->setParameter(1,"COMPASS_AUTODEC",QVariant(1)); - } - else - { - m_uas->getParamManager()->setParameter(1,"COMPASS_AUTODEC",QVariant(0)); - } - } -} - -void CompassConfig::orientationComboChanged(int index) -{ - //COMPASS_ORIENT - if (!m_uas) - { - return; - } - m_uas->getParamManager()->setParameter(1,"COMPASS_ORIENT",index); - -} diff --git a/src/ui/configuration/CompassConfig.h b/src/ui/configuration/CompassConfig.h deleted file mode 100644 index d650c1bebb89fc587934a9d3fbc70377020d2723..0000000000000000000000000000000000000000 --- a/src/ui/configuration/CompassConfig.h +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef COMPASSCONFIG_H -#define COMPASSCONFIG_H - -#include -#include "ui_CompassConfig.h" -#include "UASManager.h" -#include "UASInterface.h" -#include "AP2ConfigWidget.h" -class CompassConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit CompassConfig(QWidget *parent = 0); - ~CompassConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void enableClicked(bool enabled); - void autoDecClicked(bool enabled); - void orientationComboChanged(int index); -private: - Ui::CompassConfig ui; -}; - -#endif // COMPASSCONFIG_H diff --git a/src/ui/configuration/CompassConfig.ui b/src/ui/configuration/CompassConfig.ui deleted file mode 100644 index 95b9362b441dc7279f45a2c26adf80606b89d7ea..0000000000000000000000000000000000000000 --- a/src/ui/configuration/CompassConfig.ui +++ /dev/null @@ -1,196 +0,0 @@ - - - CompassConfig - - - - 0 - 0 - 565 - 241 - - - - Form - - - - - 10 - 0 - 521 - 31 - - - - <h2>Compass</h2> - - - false - - - - - - 230 - 100 - 101 - 16 - - - - <a href="http://magnetic-declination.com/">Declination Website</a> - - - - - - 280 - 120 - 201 - 22 - - - - - - - 290 - 180 - 101 - 23 - - - - Live Calibration - - - - - - 390 - 180 - 101 - 23 - - - - Log Calibration - - - - - - 340 - 160 - 91 - 16 - - - - Advanced Config - - - - - - 220 - 70 - 321 - 31 - - - - - - - - - - in Degrees eg 2* 3' W is -2.3 - - - - - - - - - 10 - 70 - 211 - 111 - - - - - - - - 100 - 100 - - - - - - - :/files/images/devices/BR-HMC5883-01-2.jpg - - - true - - - - - - - - - Enable - - - - - - - Auto Declination - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - 220 - 120 - 54 - 20 - - - - Orientation - - - - - - - - diff --git a/src/ui/configuration/FailSafeConfig.cc b/src/ui/configuration/FailSafeConfig.cc deleted file mode 100644 index f032541b1c7e35f44a15ddf1c3b25a0fd1e681bb..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FailSafeConfig.cc +++ /dev/null @@ -1,447 +0,0 @@ -#include "FailSafeConfig.h" - - -FailSafeConfig::FailSafeConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - ui.radio1In->setName("Radio 1"); - ui.radio1In->setMin(800); - ui.radio1In->setMax(2200); - ui.radio1In->setOrientation(Qt::Horizontal); - ui.radio2In->setName("Radio 2"); - ui.radio2In->setMin(800); - ui.radio2In->setMax(2200); - ui.radio2In->setOrientation(Qt::Horizontal); - ui.radio3In->setName("Radio 3"); - ui.radio3In->setMin(800); - ui.radio3In->setMax(2200); - ui.radio3In->setOrientation(Qt::Horizontal); - ui.radio4In->setName("Radio 4"); - ui.radio4In->setMin(800); - ui.radio4In->setMax(2200); - ui.radio4In->setOrientation(Qt::Horizontal); - ui.radio5In->setName("Radio 5"); - ui.radio5In->setMin(800); - ui.radio5In->setMax(2200); - ui.radio5In->setOrientation(Qt::Horizontal); - ui.radio6In->setName("Radio 6"); - ui.radio6In->setMin(800); - ui.radio6In->setMax(2200); - ui.radio6In->setOrientation(Qt::Horizontal); - ui.radio7In->setName("Radio 7"); - ui.radio7In->setMin(800); - ui.radio7In->setMax(2200); - ui.radio7In->setOrientation(Qt::Horizontal); - ui.radio8In->setName("Radio 8"); - ui.radio8In->setMin(800); - ui.radio8In->setMax(2200); - ui.radio8In->setOrientation(Qt::Horizontal); - - ui.radio1Out->setName("Radio 1"); - ui.radio1Out->setMin(800); - ui.radio1Out->setMax(2200); - ui.radio1Out->setOrientation(Qt::Horizontal); - ui.radio2Out->setName("Radio 2"); - ui.radio2Out->setMin(800); - ui.radio2Out->setMax(2200); - ui.radio2Out->setOrientation(Qt::Horizontal); - ui.radio3Out->setName("Radio 3"); - ui.radio3Out->setMin(800); - ui.radio3Out->setMax(2200); - ui.radio3Out->setOrientation(Qt::Horizontal); - ui.radio4Out->setName("Radio 4"); - ui.radio4Out->setMin(800); - ui.radio4Out->setMax(2200); - ui.radio4Out->setOrientation(Qt::Horizontal); - ui.radio5Out->setName("Radio 5"); - ui.radio5Out->setMin(800); - ui.radio5Out->setMax(2200); - ui.radio5Out->setOrientation(Qt::Horizontal); - ui.radio6Out->setName("Radio 6"); - ui.radio6Out->setMin(800); - ui.radio6Out->setMax(2200); - ui.radio6Out->setOrientation(Qt::Horizontal); - ui.radio7Out->setName("Radio 7"); - ui.radio7Out->setMin(800); - ui.radio7Out->setMax(2200); - ui.radio7Out->setOrientation(Qt::Horizontal); - ui.radio8Out->setName("Radio 8"); - ui.radio8Out->setMin(800); - ui.radio8Out->setMax(2200); - ui.radio8Out->setOrientation(Qt::Horizontal); - - ui.throttleFailSafeComboBox->addItem("Disable"); - ui.throttleFailSafeComboBox->addItem("Enabled - Always TRL"); - ui.throttleFailSafeComboBox->addItem("Enabled - Continue in auto"); - - connect(ui.batteryFailCheckBox,SIGNAL(clicked(bool)),this,SLOT(batteryFailChecked(bool))); - connect(ui.fsLongCheckBox,SIGNAL(clicked(bool)),this,SLOT(fsLongClicked(bool))); - connect(ui.fsShortCheckBox,SIGNAL(clicked(bool)),this,SLOT(fsShortClicked(bool))); - connect(ui.gcsCheckBox,SIGNAL(clicked(bool)),this,SLOT(gcsChecked(bool))); - connect(ui.throttleActionCheckBox,SIGNAL(clicked(bool)),this,SLOT(throttleActionChecked(bool))); - connect(ui.throttleCheckBox,SIGNAL(clicked(bool)),this,SLOT(throttleChecked(bool))); - connect(ui.throttlePwmSpinBox,SIGNAL(editingFinished()),this,SLOT(throttlePwmChanged())); - connect(ui.throttleFailSafeComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(throttleFailSafeChanged(int))); - - ui.armedLabel->setText("

DISARMED

"); - - - ui.modeLabel->setText("

MODE

"); - initConnections(); -} -void FailSafeConfig::gcsChecked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->setParameter(1,"FS_GCS_ENABL",1); - } - else - { - m_uas->setParameter(1,"FS_GCS_ENABL",0); - } -} - -void FailSafeConfig::throttleActionChecked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->setParameter(1,"THR_FS_ACTION",1); - } - else - { - m_uas->setParameter(1,"THR_FS_ACTION",0); - } -} - -void FailSafeConfig::throttleChecked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->setParameter(1,"THR_FAILSAFE",1); - } - else - { - m_uas->setParameter(1,"THR_FAILSAFE",0); - } -} - -void FailSafeConfig::throttlePwmChanged() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->setParameter(1,"THR_FS_VALUE",ui.throttlePwmSpinBox->value()); -} - -void FailSafeConfig::throttleFailSafeChanged(int index) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->setParameter(1,"FS_THR_ENABLE",index); -} - -void FailSafeConfig::fsLongClicked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->setParameter(1,"FS_LONG_ACTN",1); - } - else - { - m_uas->setParameter(1,"FS_LONG_ACTN",0); - } -} - -void FailSafeConfig::fsShortClicked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->setParameter(1,"FS_SHORT_ACTN",1); - } - else - { - m_uas->setParameter(1,"FS_SHORT_ACTN",0); - } -} - -void FailSafeConfig::batteryFailChecked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - if (checked) - { - m_uas->setParameter(1,"FS_BATT_ENABLE",1); - } - else - { - m_uas->setParameter(1,"FS_BATT_ENABLE",0); - } -} - -FailSafeConfig::~FailSafeConfig() -{ -} -void FailSafeConfig::activeUASSet(UASInterface *uas) -{ - if (m_uas) - { - disconnect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float))); - disconnect(m_uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float))); - disconnect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool))); - } - AP2ConfigWidget::activeUASSet(uas); - if (!uas) - { - return; - } - connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float))); - connect(m_uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float))); - connect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool))); - connect(m_uas,SIGNAL(gpsLocalizationChanged(UASInterface*,int)),this,SLOT(gpsStatusChanged(UASInterface*,int))); - if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING) - { - ui.batteryFailCheckBox->setVisible(false); - ui.throttleFailSafeComboBox->setVisible(false); - ui.batteryVoltSpinBox->setVisible(false); - ui.label_6->setVisible(false); - - ui.throttlePwmSpinBox->setVisible(true); //Both - - ui.throttleCheckBox->setVisible(true); - ui.throttleActionCheckBox->setVisible(true); - ui.gcsCheckBox->setVisible(true); - ui.fsLongCheckBox->setVisible(true); - ui.fsShortCheckBox->setVisible(true); - } - else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR) - { - ui.batteryFailCheckBox->setVisible(true); - ui.throttleFailSafeComboBox->setVisible(true); - ui.batteryVoltSpinBox->setVisible(true); - ui.label_6->setVisible(true); - - ui.throttlePwmSpinBox->setVisible(true); //Both - - ui.throttleCheckBox->setVisible(false); - ui.throttleActionCheckBox->setVisible(false); - ui.gcsCheckBox->setVisible(false); - ui.fsLongCheckBox->setVisible(false); - ui.fsShortCheckBox->setVisible(false); - } - else - { - //Show all, just in case - ui.batteryFailCheckBox->setVisible(true); - ui.throttleFailSafeComboBox->setVisible(true); - ui.batteryVoltSpinBox->setVisible(true); - ui.throttlePwmSpinBox->setVisible(true); //Both - ui.throttleCheckBox->setVisible(true); - ui.throttleActionCheckBox->setVisible(true); - ui.gcsCheckBox->setVisible(true); - ui.fsLongCheckBox->setVisible(true); - ui.fsShortCheckBox->setVisible(true); - } - -} -void FailSafeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - //Arducopter - if (parameterName == "FS_THR_ENABLE") - { - ui.throttleFailSafeComboBox->setCurrentIndex(value.toInt()); - } - else if (parameterName == "FS_THR_VALUE") - { - ui.throttlePwmSpinBox->setValue(value.toFloat()); - } - else if (parameterName == "FS_BATT_ENABLE") - { - if (value.toInt() == 0) - { - ui.batteryFailCheckBox->setChecked(false); - } - else - { - ui.batteryFailCheckBox->setChecked(true); - } - } - else if (parameterName == "LOW_VOLT") - { - ui.batteryVoltSpinBox->setValue(value.toFloat()); - } - //Arduplane - else if (parameterName == "THR_FAILSAFE") - { - if (value.toInt() == 0) - { - ui.throttleCheckBox->setChecked(false); - } - else - { - ui.throttleCheckBox->setChecked(true); - } - } - else if (parameterName == "THR_FS_VALUE") - { - ui.throttlePwmSpinBox->setValue(value.toFloat()); - } - else if (parameterName == "THR_FS_ACTION") - { - if (value.toInt() == 0) - { - ui.throttleActionCheckBox->setChecked(false); - } - else - { - ui.throttleActionCheckBox->setChecked(true); - } - } - else if (parameterName == "FS_GCS_ENABL") - { - if (value.toInt() == 0) - { - ui.gcsCheckBox->setChecked(false); - } - else - { - ui.gcsCheckBox->setChecked(true); - } - } - else if (parameterName == "FS_SHORT_ACTN") - { - if (value.toInt() == 0) - { - ui.fsShortCheckBox->setChecked(false); - } - else - { - ui.fsShortCheckBox->setChecked(true); - } - } - else if (parameterName == "FS_LONG_ACTN") - { - if (value.toInt() == 0) - { - ui.fsLongCheckBox->setChecked(false); - } - else - { - ui.fsLongCheckBox->setChecked(true); - } - } - -} - -void FailSafeConfig::armingChanged(bool armed) -{ - if (armed) - { - ui.armedLabel->setText("

ARMED

"); - } - else - { - ui.armedLabel->setText("

DISARMED

"); - } -} - -void FailSafeConfig::remoteControlChannelRawChanges(int chan,float value) -{ - if (chan == 0) - { - ui.radio1In->setValue(value); - } - else if (chan == 1) - { - ui.radio2In->setValue(value); - } - else if (chan == 2) - { - ui.radio3In->setValue(value); - } - else if (chan == 3) - { - ui.radio4In->setValue(value); - } - else if (chan == 4) - { - ui.radio5In->setValue(value); - } - else if (chan == 5) - { - ui.radio6In->setValue(value); - } - else if (chan == 6) - { - ui.radio7In->setValue(value); - } - else if (chan == 7) - { - ui.radio8In->setValue(value); - } -} -void FailSafeConfig::hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8) -{ - Q_UNUSED(time); - - ui.radio1Out->setValue(act1); - ui.radio2Out->setValue(act2); - ui.radio3Out->setValue(act3); - ui.radio4Out->setValue(act4); - ui.radio5Out->setValue(act5); - ui.radio6Out->setValue(act6); - ui.radio7Out->setValue(act7); - ui.radio8Out->setValue(act8); -} -void FailSafeConfig::gpsStatusChanged(UASInterface* uas,int fixtype) -{ - Q_UNUSED(uas); - - if (fixtype == 0 || fixtype == 1) - { - ui.gpsLabel->setText("

None

"); - } - else if (fixtype == 2) - { - ui.gpsLabel->setText("

2D Fix

"); - } - else if (fixtype == 3) - { - ui.gpsLabel->setText("

3D Fix

"); - } -} diff --git a/src/ui/configuration/FailSafeConfig.h b/src/ui/configuration/FailSafeConfig.h deleted file mode 100644 index 82467393122121d0d2bc696ff65ee2131a2d9e40..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FailSafeConfig.h +++ /dev/null @@ -1,33 +0,0 @@ -#ifndef FAILSAFECONFIG_H -#define FAILSAFECONFIG_H - -#include -#include "ui_FailSafeConfig.h" -#include "AP2ConfigWidget.h" -class FailSafeConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit FailSafeConfig(QWidget *parent = 0); - ~FailSafeConfig(); -private slots: - void activeUASSet(UASInterface *uas); - void remoteControlChannelRawChanges(int chan,float value); - void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8); - void armingChanged(bool armed); - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void batteryFailChecked(bool checked); - void fsLongClicked(bool checked); - void fsShortClicked(bool checked); - void gcsChecked(bool checked); - void throttleActionChecked(bool checked); - void throttleChecked(bool checked); - void throttlePwmChanged(); - void throttleFailSafeChanged(int index); - void gpsStatusChanged(UASInterface* uas,int fixtype); -private: - Ui::FailSafeConfig ui; -}; - -#endif // FAILSAFECONFIG_H diff --git a/src/ui/configuration/FailSafeConfig.ui b/src/ui/configuration/FailSafeConfig.ui deleted file mode 100644 index 69375dd53599967a7c06b48b2aeb1f2f3213397c..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FailSafeConfig.ui +++ /dev/null @@ -1,452 +0,0 @@ - - - FailSafeConfig - - - - 0 - 0 - 822 - 536 - - - - Form - - - - - 20 - 20 - 141 - 31 - - - - <h2>Fail Safe</h2> - - - - - - 20 - 70 - 252 - 441 - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - - 300 - 70 - 252 - 441 - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - - 570 - 60 - 181 - 181 - - - - Status - - - - - - TextLabel - - - - - - - TextLabel - - - - - - - TextLabel - - - - - - - - - 570 - 250 - 161 - 261 - - - - Failsafe Options - - - - - - Throttle FailSafe - - - - - - - - - - - - FS Pwm - - - - - - - 3000 - - - - - - - - - Throttle FailSafe Action - - - - - - - GCS FailSafe - - - - - - - FailSafe Short (1 sec) - - - - - - - FailSafe Long (20 sec) - - - - - - - Battery Failsafe - - - - - - - - - Low Battery - - - - - - - 100.000000000000000 - - - - - - - - - - - QGCRadioChannelDisplay - QWidget -
ui/designer/QGCRadioChannelDisplay.h
- 1 -
-
- - -
diff --git a/src/ui/configuration/FlightModeConfig.cc b/src/ui/configuration/FlightModeConfig.cc deleted file mode 100644 index 7939fac5bf564a22d05ef88b8bb5fac5259f0476..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FlightModeConfig.cc +++ /dev/null @@ -1,285 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -#include "FlightModeConfig.h" - -// We used the _rgModeInfo* arrays to populate the combo box choices. The numeric value -// is the flight mode value that corresponds to the label. We store that value in the -// combo box item data. There is a different set or each vehicle type. - -const FlightModeConfig::FlightModeInfo_t FlightModeConfig::_rgModeInfoFixedWing[] = { - { "Manual", 0 }, - { "Circle", 1 }, - { "Stabilize", 2 }, - { "Training", 3 }, - { "FBW A", 5 }, - { "FBW B", 6 }, - { "Auto", 10 }, - { "RTL", 11 }, - { "Loiter", 12 }, - { "Guided", 15 }, -}; - -const FlightModeConfig::FlightModeInfo_t FlightModeConfig::_rgModeInfoRotor[] = { - { "Stabilize", 0 }, - { "Acro", 1 }, - { "Alt Hold", 2 }, - { "Auto", 3 }, - { "Guided", 4 }, - { "Loiter", 5 }, - { "RTL", 6 }, - { "Circle", 7 }, - { "Position", 8 }, - { "Land", 9 }, - { "OF_Loiter", 10 }, - { "Toy A", 11 }, - { "Toy M", 12 }, -}; - -const FlightModeConfig::FlightModeInfo_t FlightModeConfig::_rgModeInfoRover[] = { - { "Manual", 0 }, - { "Learning", 2 }, - { "Steering", 3 }, - { "Hold", 4 }, - { "Auto", 10 }, - { "RTL", 11 }, - { "Guided", 15 }, -}; - -// We use the _rgModeParam* arrays to store the parameter names for each selectable -// flight mode. The order of these corresponds to the combox box order as well. Array -// element 0, is the parameter for mode0ComboBox, array element 1 = mode1ComboBox and -// so on. The number of elements in the array also determines how many combo boxes we -// are going to need. Different vehicle types have different numbers of selectable -// flight modes. - -const char* FlightModeConfig::_rgModeParamFixedWing[_cModes] = { "FLTMODE1", "FLTMODE2", "FLTMODE3", "FLTMODE4", "FLTMODE5", "FLTMODE6" }; - -const char* FlightModeConfig::_rgModeParamRotor[_cModes] = { "FLTMODE1", "FLTMODE2", "FLTMODE3", "FLTMODE4", "FLTMODE5", "FLTMODE6" }; - -const char* FlightModeConfig::_rgModeParamRover[_cModes] = { "MODE1", "MODE2", "MODE3", "MODE4", "MODE5", "MODE6" }; - -// Parameter which contains simple mode bitmask -const char* FlightModeConfig::_simpleModeBitMaskParam = "SIMPLE"; - -// Parameter which controls which RC channel mode switching is on. -// ArduCopter is hardcoded so no param -const char* FlightModeConfig::_modeSwitchRCChannelParamFixedWing = "FLTMODE_CH"; -const char* FlightModeConfig::_modeSwitchRCChannelParamRover = "MODE_CH"; - -// PWM values which are the boundaries between each mode selection -const int FlightModeConfig::_rgModePWMBoundary[_cModes] = { 1230, 1360, 1490, 1620, 1749, 20000 }; - -FlightModeConfig::FlightModeConfig(QWidget *parent) : - AP2ConfigWidget(parent), - _rgModeInfo(NULL), - _cModeInfo(0), - _rgModeParam(NULL), - _simpleModeSupported(false), - _modeSwitchRCChannel(_modeSwitchRCChannelInvalid) -{ - _ui.setupUi(this); - - // Find all the widgets we are going to programmatically control - for (size_t i=0; i<_cModes; i++) { - _rgLabel[i] = findChild(QString("mode%1Label").arg(i)); - _rgCombo[i] = findChild(QString("mode%1ComboBox").arg(i)); - _rgSimpleModeCheckBox[i] = findChild(QString("mode%1SimpleCheckBox").arg(i)); - _rgPWMLabel[i] = findChild(QString("mode%1PWMLabel").arg(i)); - Q_ASSERT(_rgLabel[i]); - Q_ASSERT(_rgCombo[i]); - Q_ASSERT(_rgSimpleModeCheckBox[i]); - Q_ASSERT(_rgPWMLabel[i]); - } - - // Start disabled until we get a UAS - setEnabled(false); - - connect(_ui.savePushButton, SIGNAL(clicked()), this, SLOT(saveButtonClicked())); - initConnections(); -} - -void FlightModeConfig::activeUASSet(UASInterface *uas) -{ - // Clear the highlighting on PWM labels - for (size_t i=0; i<_cModes; i++) { - _rgPWMLabel[i]->setStyleSheet(QString("")); - } - - // Disconnect from old UAS - if (m_uas) - { - disconnect(m_uas, SIGNAL(remoteControlChannelRawChanged(int, float)), this, SLOT(remoteControlChannelRawChanged(int, float))); - } - - // Connect to new UAS (if any) - AP2ConfigWidget::activeUASSet(uas); - if (!uas) { - setEnabled(false); - return; - } - connect(m_uas, SIGNAL(remoteControlChannelRawChanged(int, float)), this, SLOT(remoteControlChannelRawChanged(int, float))); - setEnabled(true); - - // Select the correct set of Flight Modes and Flight Mode Parameters. If the rc channel - // associated with the mode switch is settable through a param, it is invalid until - // we get that param through. - switch (m_uas->getSystemType()) { - case MAV_TYPE_FIXED_WING: - _rgModeInfo = &_rgModeInfoFixedWing[0]; - _cModeInfo = sizeof(_rgModeInfoFixedWing)/sizeof(_rgModeInfoFixedWing[0]); - _rgModeParam = _rgModeParamFixedWing; - _simpleModeSupported = false; - _modeSwitchRCChannelParam = _modeSwitchRCChannelParamFixedWing; - _modeSwitchRCChannel = _modeSwitchRCChannelInvalid; - break; - case MAV_TYPE_GROUND_ROVER: - _rgModeInfo = &_rgModeInfoRover[0]; - _cModeInfo = sizeof(_rgModeInfoRover)/sizeof(_rgModeInfoRover[0]); - _rgModeParam = _rgModeParamRover; - _simpleModeSupported = false; - _modeSwitchRCChannelParam = _modeSwitchRCChannelParamRover; - _modeSwitchRCChannel = _modeSwitchRCChannelInvalid; - break; - case MAV_TYPE_QUADROTOR: - case MAV_TYPE_TRICOPTER: - case MAV_TYPE_HEXAROTOR: - case MAV_TYPE_OCTOROTOR: - case MAV_TYPE_HELICOPTER: - _rgModeInfo = &_rgModeInfoRotor[0]; - _cModeInfo = sizeof(_rgModeInfoRotor)/sizeof(_rgModeInfoRotor[0]); - _rgModeParam = _rgModeParamRotor; - _simpleModeSupported = true; - _modeSwitchRCChannelParam = NULL; - _modeSwitchRCChannel = _modeSwitchRCChannelRotor; // Rotor is harcoded - break; - default: - // We've gotten a mav type we can't handle, just disable to whole thing - qDebug() << QString("Unknown System Type %1").arg(m_uas->getSystemType()); - setEnabled(false); - return; - } - - // Set up the combo boxes - for (int i=0; i<_cModes; i++) { - // Fill each combo box with the available flight modes - for (int j=0; j<_cModeInfo; j++) { - _rgCombo[i]->addItem(_rgModeInfo[j].label, QVariant(QChar((char)_rgModeInfo[j].value))); - } - - // Not all vehicle types support simple mode, hide/show as appropriate - _rgSimpleModeCheckBox[i]->setEnabled(_simpleModeSupported); - } -} - -void FlightModeConfig::saveButtonClicked(void) -{ - // Save the current setting for each flight mode slot - for (size_t i=0; i<_cModes; i++) { - m_uas->getParamManager()->setParameter(1, _rgModeParam[i], _rgCombo[i]->itemData(_rgCombo[i]->currentIndex())); - QVariant var =_rgCombo[i]->itemData(_rgCombo[i]->currentIndex()); - } - - // Save Simple Mode bit mask if supported - if (_simpleModeSupported) { - int bitMask = 0; - for (size_t i=0; i<_cModes; i++) { - if (_rgSimpleModeCheckBox[i]->isChecked()) { - bitMask |= 1 << i; - } - } - m_uas->getParamManager()->setParameter(1, _simpleModeBitMaskParam, QVariant(QChar(bitMask))); - } -} - -// Higlights the PWM label for currently selected mode according the mode switch -// rc channel value. -void FlightModeConfig::remoteControlChannelRawChanged(int chan, float val) -{ - // Until we get the _modeSwitchRCChannel value from a parameter it will be set - // to -1, which is an invalid channel thus the labels won't update - if (chan == _modeSwitchRCChannel) - { - size_t highlightIndex = _cModes; // initialize to unreachable index - - for (size_t i=0; i<_cModes; i++) { - if (val < _rgModePWMBoundary[i]) { - highlightIndex = i; - break; - } - } - - for (size_t i=0; i<_cModes; i++) { - QString styleSheet; - if (i == highlightIndex) { - styleSheet = "background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"; - } else { - styleSheet = ""; - } - _rgPWMLabel[i]->setStyleSheet(styleSheet); - } - } -} - -void FlightModeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - int iValue = value.toInt(); - - if (parameterName == _modeSwitchRCChannelParam) { - _modeSwitchRCChannel = iValue - 1; // 1-based in params - } else if (parameterName == _simpleModeBitMaskParam) { - if (_simpleModeSupported) { - for (size_t i=0; i<_cModes; i++) { - _rgSimpleModeCheckBox[i]->setCheckState((iValue & (1 << i)) ? Qt::Checked : Qt::Unchecked); - } - } else { - qDebug() << "Received simple mode parameter on non simple mode vehicle type"; - } - } else { - // Loop over the flight mode params looking for a match - for (int i=0; i<_cModes; i++) { - if (parameterName == _rgModeParam[i]) { - // We found a match, i is now the index of the combo box which displays that mode slot - // Loop over the mode info till we find the matching value, this tells us which row in the - // combo box to select. - QComboBox* combo = _rgCombo[i]; - for (int j=0; j<_cModeInfo; j++) { - if (_rgModeInfo[j].value == iValue) { - combo->setCurrentIndex(j); - return; - } - } - - // We should have been able to find the flight mode value. If we didn't, we have been passed a - // flight mode that we don't understand. Possibly a newer firmware version we are not yet up - // to date with. In this case, add a new item to the combo box to represent it. - qDebug() << QString("Unknown flight mode value %1").arg(iValue); - combo->addItem(QString("%1 - Unknown").arg(iValue), QVariant(iValue)); - combo->setCurrentIndex(combo->count() - 1); - } - } - } -} diff --git a/src/ui/configuration/FlightModeConfig.h b/src/ui/configuration/FlightModeConfig.h deleted file mode 100644 index 81ee2939fc47d07d75237ef53e0ebf56ff7185ce..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FlightModeConfig.h +++ /dev/null @@ -1,89 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -#ifndef FLIGHTMODECONFIG_H -#define FLIGHTMODECONFIG_H - -#include -#include -#include "ui_FlightModeConfig.h" -#include "AP2ConfigWidget.h" - -class FlightModeConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit FlightModeConfig(QWidget *parent = 0); - -private slots: - // Overrides from AP2ConfigWidget - virtual void activeUASSet(UASInterface *uas); - virtual void parameterChanged(int uas, int component, QString parameterName, QVariant value); - - // Signalled from UAS - void remoteControlChannelRawChanged(int chan,float val); - - // Signalled from FlightModeConfig UI - void saveButtonClicked(void); - - -private: - typedef struct { - const char* label; - int value; - } FlightModeInfo_t; - - static const FlightModeInfo_t _rgModeInfoFixedWing[]; - static const FlightModeInfo_t _rgModeInfoRotor[]; - static const FlightModeInfo_t _rgModeInfoRover[]; - const FlightModeInfo_t* _rgModeInfo; - int _cModeInfo; - - static const int _cModes = 6; - - static const char* _rgModeParamFixedWing[_cModes]; - static const char* _rgModeParamRotor[_cModes]; - static const char* _rgModeParamRover[_cModes]; - const char** _rgModeParam; - - static const int _rgModePWMBoundary[_cModes]; - - bool _simpleModeSupported; - static const char* _simpleModeBitMaskParam; - - static const char* _modeSwitchRCChannelParamFixedWing; - static const char* _modeSwitchRCChannelParamRover; - const char* _modeSwitchRCChannelParam; - static const int _modeSwitchRCChannelRotor = 4; // ArduCopter harcoded to 0-based channel 4 - static const int _modeSwitchRCChannelInvalid = -1; - int _modeSwitchRCChannel; - - QLabel* _rgLabel[_cModes]; - QComboBox* _rgCombo[_cModes]; - QCheckBox* _rgSimpleModeCheckBox[_cModes]; - QLabel* _rgPWMLabel[_cModes]; - Ui::FlightModeConfig _ui; -}; - -#endif // FLIGHTMODECONFIG_H diff --git a/src/ui/configuration/FlightModeConfig.ui b/src/ui/configuration/FlightModeConfig.ui deleted file mode 100644 index 9e3a5ae6b440f7e03bd414971fcd61e37f96e45e..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FlightModeConfig.ui +++ /dev/null @@ -1,276 +0,0 @@ - - - FlightModeConfig - - - - 0 - 0 - 818 - 435 - - - - Form - - - - - 10 - 20 - 131 - 31 - - - - <h2>Flight Modes</h2> - - - false - - - - - - 20 - 70 - 481 - 191 - - - - - - - -1 - - - 0 - - - - - Flight Mode 1 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Flight Mode 2 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Flight Mode 3 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Flight Mode 4 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Flight Mode 5 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Flight Mode 6 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - 0 - - - - - - 0 - 0 - - - - true - - - - - - - - - - - - - - - - - - - - - - - - - - - - 12 - - - 0 - - - - - Simple Mode - - - - - - - Simple Mode - - - - - - - Simple Mode - - - - - - - Simple Mode - - - - - - - Simple Mode - - - - - - - Simple Mode - - - - - - - - - -1 - - - - - - - - PWM 0 - 1230 - - - - - - - PWM 1231 - 1360 - - - - - - - PWM 1361 - 1490 - - - - - - - PWM 1491 - 1620 - - - - - - - PWM 1621 - 1749 - - - - - - - - - - PWM 1750 + - - - - - - - - - - - 50 - 290 - 75 - 23 - - - - Save - - - - - - diff --git a/src/ui/configuration/FrameTypeConfig.cc b/src/ui/configuration/FrameTypeConfig.cc deleted file mode 100644 index 9d8803c264f76153dd4e0a411342e8775cbe68dc..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FrameTypeConfig.cc +++ /dev/null @@ -1,106 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2013 Michael Carpenter (malcom2073@gmail.com) - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Airframe type configuration widget source. - * - * @author Michael Carpenter - * - */ - -#include "FrameTypeConfig.h" - - -FrameTypeConfig::FrameTypeConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - - //Disable until we get a FRAME parameter. - ui.xRadioButton->setEnabled(false); - ui.vRadioButton->setEnabled(false); - ui.plusRadioButton->setEnabled(false); - - connect(ui.plusRadioButton,SIGNAL(clicked()),this,SLOT(plusFrameSelected())); - connect(ui.xRadioButton,SIGNAL(clicked()),this,SLOT(xFrameSelected())); - connect(ui.vRadioButton,SIGNAL(clicked()),this,SLOT(vFrameSelected())); - initConnections(); -} - -FrameTypeConfig::~FrameTypeConfig() -{ -} -void FrameTypeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "FRAME") - { - ui.xRadioButton->setEnabled(true); - ui.vRadioButton->setEnabled(true); - ui.plusRadioButton->setEnabled(true); - if (value.toInt() == 0) - { - ui.plusRadioButton->setChecked(true); - } - else if (value.toInt() == 1) - { - ui.xRadioButton->setChecked(true); - } - else if (value.toInt() == 2) - { - ui.vRadioButton->setChecked(true); - } - } -} - -void FrameTypeConfig::xFrameSelected() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"FRAME",QVariant(1)); -} - -void FrameTypeConfig::plusFrameSelected() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"FRAME",QVariant(0)); -} - -void FrameTypeConfig::vFrameSelected() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"FRAME",QVariant(2)); -} diff --git a/src/ui/configuration/FrameTypeConfig.h b/src/ui/configuration/FrameTypeConfig.h deleted file mode 100644 index f52e92369e920c1f92ab74ebc9f6d7e02c6bcbe6..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FrameTypeConfig.h +++ /dev/null @@ -1,55 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2013 Michael Carpenter (malcom2073@gmail.com) - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Airframe type configuration widget header. - * - * @author Michael Carpenter - * - */ - -#ifndef FRAMETYPECONFIG_H -#define FRAMETYPECONFIG_H - -#include -#include "ui_FrameTypeConfig.h" -#include "AP2ConfigWidget.h" - -class FrameTypeConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit FrameTypeConfig(QWidget *parent = 0); - ~FrameTypeConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void xFrameSelected(); - void plusFrameSelected(); - void vFrameSelected(); -private: - Ui::FrameTypeConfig ui; -}; - -#endif // FRAMETYPECONFIG_H diff --git a/src/ui/configuration/FrameTypeConfig.ui b/src/ui/configuration/FrameTypeConfig.ui deleted file mode 100644 index 6787fa5dbc17d6f27fdfeeb689e766c4dc49b44d..0000000000000000000000000000000000000000 --- a/src/ui/configuration/FrameTypeConfig.ui +++ /dev/null @@ -1,107 +0,0 @@ - - - FrameTypeConfig - - - - 0 - 0 - 553 - 497 - - - - Form - - - - - - <h2>Frame Setup</h2> - - - false - - - - - - - - - 'Plus' Style - - - - :/files/images/mavs/frames_plus.png:/files/images/mavs/frames_plus.png - - - - 300 - 150 - - - - - - - - 'X' Style - - - - :/files/images/mavs/frames_x.png:/files/images/mavs/frames_x.png - - - - 300 - 150 - - - - - - - - Qt::LeftToRight - - - false - - - 'V' Style - - - - :/files/images/mavs/frames-05.png:/files/images/mavs/frames-05.png - - - - 300 - 120 - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - diff --git a/src/ui/configuration/GeoFenceConfig.cc b/src/ui/configuration/GeoFenceConfig.cc deleted file mode 100644 index ea01a4b248aa781b46c20fa384402a0dbff6502d..0000000000000000000000000000000000000000 --- a/src/ui/configuration/GeoFenceConfig.cc +++ /dev/null @@ -1,11 +0,0 @@ -#include "GeoFenceConfig.h" - - -GeoFenceConfig::GeoFenceConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); -} - -GeoFenceConfig::~GeoFenceConfig() -{ -} diff --git a/src/ui/configuration/GeoFenceConfig.h b/src/ui/configuration/GeoFenceConfig.h deleted file mode 100644 index 71624346d7c009b4284bb06937bccfb5e7772026..0000000000000000000000000000000000000000 --- a/src/ui/configuration/GeoFenceConfig.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef GEOFENCECONFIG_H -#define GEOFENCECONFIG_H - -#include -#include "ui_GeoFenceConfig.h" - -class GeoFenceConfig : public QWidget -{ - Q_OBJECT - -public: - explicit GeoFenceConfig(QWidget *parent = 0); - ~GeoFenceConfig(); - -private: - Ui::GeoFenceConfig ui; -}; - -#endif // GEOFENCECONFIG_H diff --git a/src/ui/configuration/GeoFenceConfig.ui b/src/ui/configuration/GeoFenceConfig.ui deleted file mode 100644 index b51ea2e5083aa2ffe8cedff24cf37228206d76a8..0000000000000000000000000000000000000000 --- a/src/ui/configuration/GeoFenceConfig.ui +++ /dev/null @@ -1,32 +0,0 @@ - - - GeoFenceConfig - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - 20 - 20 - 141 - 51 - - - - <h2>Geo Fence</h2> - - - - - - diff --git a/src/ui/configuration/OpticalFlowConfig.cc b/src/ui/configuration/OpticalFlowConfig.cc deleted file mode 100644 index 89f30558208e1cfcb8435c2ff438a7476a40a8c5..0000000000000000000000000000000000000000 --- a/src/ui/configuration/OpticalFlowConfig.cc +++ /dev/null @@ -1,40 +0,0 @@ -#include "OpticalFlowConfig.h" -#include - -OpticalFlowConfig::OpticalFlowConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - connect(ui.enableCheckBox,SIGNAL(clicked(bool)),this,SLOT(enableCheckBoxClicked(bool))); - initConnections(); -} - -OpticalFlowConfig::~OpticalFlowConfig() -{ -} -void OpticalFlowConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "FLOW_ENABLE") - { - if (value.toInt() == 0) - { - ui.enableCheckBox->setChecked(false); - } - else - { - ui.enableCheckBox->setChecked(true); - } - } -} - -void OpticalFlowConfig::enableCheckBoxClicked(bool checked) -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"FLOW_ENABLE",checked ? 1 : 0); -} diff --git a/src/ui/configuration/OpticalFlowConfig.h b/src/ui/configuration/OpticalFlowConfig.h deleted file mode 100644 index 38b4ae7ebb83f565a80a315ad11d870bf89fc0f3..0000000000000000000000000000000000000000 --- a/src/ui/configuration/OpticalFlowConfig.h +++ /dev/null @@ -1,22 +0,0 @@ -#ifndef OPTICALFLOWCONFIG_H -#define OPTICALFLOWCONFIG_H - -#include -#include "AP2ConfigWidget.h" -#include "ui_OpticalFlowConfig.h" - -class OpticalFlowConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit OpticalFlowConfig(QWidget *parent = 0); - ~OpticalFlowConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void enableCheckBoxClicked(bool checked); -private: - Ui::OpticalFlowConfig ui; -}; - -#endif // OPTICALFLOWCONFIG_H diff --git a/src/ui/configuration/OpticalFlowConfig.ui b/src/ui/configuration/OpticalFlowConfig.ui deleted file mode 100644 index e5a5bce4c6406af6cb060bce8447517871586632..0000000000000000000000000000000000000000 --- a/src/ui/configuration/OpticalFlowConfig.ui +++ /dev/null @@ -1,69 +0,0 @@ - - - OpticalFlowConfig - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - 20 - 20 - 131 - 31 - - - - <h2>Optical Flow</h2> - - - false - - - - - - 100 - 60 - 70 - 17 - - - - Enable - - - - - - 10 - 60 - 81 - 71 - - - - - - - :/files/images/devices/BR-0016-01-3T.jpg - - - true - - - - - - - - diff --git a/src/ui/configuration/OsdConfig.cc b/src/ui/configuration/OsdConfig.cc deleted file mode 100644 index e3280a9c86607e1de0d99c300cba22691a425341..0000000000000000000000000000000000000000 --- a/src/ui/configuration/OsdConfig.cc +++ /dev/null @@ -1,30 +0,0 @@ -#include "OsdConfig.h" -#include - -OsdConfig::OsdConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - connect(ui.enablePushButton,SIGNAL(clicked()),this,SLOT(enableButtonClicked())); - initConnections(); - -} - -OsdConfig::~OsdConfig() -{ -} -void OsdConfig::enableButtonClicked() -{ - if (!m_uas) - { - showNullMAVErrorMessageBox(); - return; - } - m_uas->getParamManager()->setParameter(1,"SR0_EXT_STAT",2); - m_uas->getParamManager()->setParameter(1,"SR0_EXTRA1",10); - m_uas->getParamManager()->setParameter(1,"SR0_EXTRA2",10); - m_uas->getParamManager()->setParameter(1,"SR0_EXTRA3",2); - m_uas->getParamManager()->setParameter(1,"SR0_POSITION",3); - m_uas->getParamManager()->setParameter(1,"SR0_RAW_CTRL",2); - m_uas->getParamManager()->setParameter(1,"SR0_RAW_SENS",2); - m_uas->getParamManager()->setParameter(1,"SR0_RC_CHAN",2); -} diff --git a/src/ui/configuration/OsdConfig.h b/src/ui/configuration/OsdConfig.h deleted file mode 100644 index 963fa0dd1a507b8f1d0f1a4e9ad072326d11512b..0000000000000000000000000000000000000000 --- a/src/ui/configuration/OsdConfig.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef OSDCONFIG_H -#define OSDCONFIG_H - -#include -#include "AP2ConfigWidget.h" -#include "ui_OsdConfig.h" - -class OsdConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit OsdConfig(QWidget *parent = 0); - ~OsdConfig(); -private slots: - void enableButtonClicked(); -private: - Ui::OsdConfig ui; -}; - -#endif // OSDCONFIG_H diff --git a/src/ui/configuration/OsdConfig.ui b/src/ui/configuration/OsdConfig.ui deleted file mode 100644 index 6c9e4d7aece4e8246d56d24fd691a2e4e06b94d6..0000000000000000000000000000000000000000 --- a/src/ui/configuration/OsdConfig.ui +++ /dev/null @@ -1,85 +0,0 @@ - - - OsdConfig - - - - 0 - 0 - 499 - 243 - - - - Form - - - - - 20 - 20 - 131 - 31 - - - - <h2>OSD</h2> - - - false - - - - - - 10 - 60 - 101 - 41 - - - - - - - :/files/images/devices/MinimOSD.jpg - - - true - - - - - - 230 - 60 - 191 - 41 - - - - You only need to use this if you are -having issue with your OSD not -updating - - - - - - 120 - 60 - 91 - 41 - - - - Enable -Telemetry - - - - - - - - diff --git a/src/ui/configuration/Radio3DRConfig.cc b/src/ui/configuration/Radio3DRConfig.cc deleted file mode 100644 index 435ae290f92f2bc05c417f86c3c8716b810a2946..0000000000000000000000000000000000000000 --- a/src/ui/configuration/Radio3DRConfig.cc +++ /dev/null @@ -1,11 +0,0 @@ -#include "Radio3DRConfig.h" - - -Radio3DRConfig::Radio3DRConfig(QWidget *parent) : QWidget(parent) -{ - ui.setupUi(this); -} - -Radio3DRConfig::~Radio3DRConfig() -{ -} diff --git a/src/ui/configuration/Radio3DRConfig.h b/src/ui/configuration/Radio3DRConfig.h deleted file mode 100644 index 5233921d1592ca7aae68fbe9642c2a9c08fa3708..0000000000000000000000000000000000000000 --- a/src/ui/configuration/Radio3DRConfig.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef RADIO3DRCONFIG_H -#define RADIO3DRCONFIG_H - -#include -#include "ui_Radio3DRConfig.h" - -class Radio3DRConfig : public QWidget -{ - Q_OBJECT - -public: - explicit Radio3DRConfig(QWidget *parent = 0); - ~Radio3DRConfig(); - -private: - Ui::Radio3DRConfig ui; -}; - -#endif // RADIO3DRCONFIG_H diff --git a/src/ui/configuration/Radio3DRConfig.ui b/src/ui/configuration/Radio3DRConfig.ui deleted file mode 100644 index 7a98b9dba7db8ce30c2de14706483a9924b6076d..0000000000000000000000000000000000000000 --- a/src/ui/configuration/Radio3DRConfig.ui +++ /dev/null @@ -1,35 +0,0 @@ - - - Radio3DRConfig - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - 20 - 20 - 131 - 31 - - - - <h2>3DR Radio</h2> - - - false - - - - - - diff --git a/src/ui/configuration/RadioCalibrationConfig.cc b/src/ui/configuration/RadioCalibrationConfig.cc deleted file mode 100644 index 0de55857f244cc5eaa13c82d1076f26fb9471fea..0000000000000000000000000000000000000000 --- a/src/ui/configuration/RadioCalibrationConfig.cc +++ /dev/null @@ -1,250 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2013 Michael Carpenter (malcom2073@gmail.com) - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Radio Calibration Configuration source. - * - * @author Michael Carpenter - * - */ - -#include "RadioCalibrationConfig.h" -#include - -RadioCalibrationConfig::RadioCalibrationConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - - connect(ui.calibrateButton,SIGNAL(clicked()),this,SLOT(calibrateButtonClicked())); - m_calibrationEnabled = false; - ui.rollWidget->setMin(800); - ui.rollWidget->setMax(2200); - ui.pitchWidget->setMin(800); - ui.pitchWidget->setMax(2200); - ui.throttleWidget->setMin(800); - ui.throttleWidget->setMax(2200); - ui.yawWidget->setMin(800); - ui.yawWidget->setMax(2200); - ui.radio5Widget->setMin(800); - ui.radio5Widget->setMax(2200); - ui.radio6Widget->setMin(800); - ui.radio6Widget->setMax(2200); - ui.radio7Widget->setMin(800); - ui.radio7Widget->setMax(2200); - ui.radio8Widget->setMin(800); - ui.radio8Widget->setMax(2200); - ui.rollWidget->setOrientation(Qt::Horizontal); - ui.rollWidget->setName("Roll"); - ui.yawWidget->setOrientation(Qt::Horizontal); - ui.yawWidget->setName("Yaw"); - ui.pitchWidget->setName("Pitch"); - ui.throttleWidget->setName("Throttle"); - ui.radio5Widget->setOrientation(Qt::Horizontal); - ui.radio5Widget->setName("Radio 5"); - ui.radio6Widget->setOrientation(Qt::Horizontal); - ui.radio6Widget->setName("Radio 6"); - ui.radio7Widget->setOrientation(Qt::Horizontal); - ui.radio7Widget->setName("Radio 7"); - ui.radio8Widget->setOrientation(Qt::Horizontal); - ui.radio8Widget->setName("Radio 8"); - - guiUpdateTimer = new QTimer(this); - connect(guiUpdateTimer,SIGNAL(timeout()),this,SLOT(guiUpdateTimerTick())); - - rcMin << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0; - rcMax << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0; - rcTrim << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0; - rcValue << 0.0 << 0.0 << 0.0 << 0.0 << 0.0 << 0.0 << 0.0 << 0.0; - - initConnections(); -} - -RadioCalibrationConfig::~RadioCalibrationConfig() -{ -} -void RadioCalibrationConfig::activeUASSet(UASInterface *uas) -{ - if (m_uas) - { - disconnect(m_uas, SIGNAL(remoteControlChannelRawChanged(int,float)), this,SLOT(remoteControlChannelRawChanged(int,float))); - } - AP2ConfigWidget::activeUASSet(uas); - if (!uas) - { - return; - } - connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float))); -} -void RadioCalibrationConfig::remoteControlChannelRawChanged(int chan,float val) -{ - - //Channel is 0-7 typically? - //Val will be 0-3000, PWM value. - if (m_calibrationEnabled) { - if (val < rcMin[chan]) - { - rcMin[chan] = val; - } - - if (val > rcMax[chan]) - { - rcMax[chan] = val; - } - } - - // Raw value - rcValue[chan] = val; -} - -void RadioCalibrationConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - Q_UNUSED(parameterName); - Q_UNUSED(value); -} -void RadioCalibrationConfig::guiUpdateTimerTick() -{ - ui.rollWidget->setValue(rcValue[0]); - ui.pitchWidget->setValue(rcValue[1]); - ui.throttleWidget->setValue(rcValue[2]); - ui.yawWidget->setValue(rcValue[3]); - ui.radio5Widget->setValue(rcValue[4]); - ui.radio6Widget->setValue(rcValue[5]); - ui.radio7Widget->setValue(rcValue[6]); - ui.radio8Widget->setValue(rcValue[7]); - if (m_calibrationEnabled) - { - ui.rollWidget->setMin(rcMin[0]); - ui.rollWidget->setMax(rcMax[0]); - ui.pitchWidget->setMin(rcMin[1]); - ui.pitchWidget->setMax(rcMax[1]); - ui.throttleWidget->setMin(rcMin[2]); - ui.throttleWidget->setMax(rcMax[2]); - ui.yawWidget->setMin(rcMin[3]); - ui.yawWidget->setMax(rcMax[3]); - ui.radio5Widget->setMin(rcMin[4]); - ui.radio5Widget->setMax(rcMax[4]); - ui.radio6Widget->setMin(rcMin[5]); - ui.radio6Widget->setMax(rcMax[5]); - ui.radio7Widget->setMin(rcMin[6]); - ui.radio7Widget->setMax(rcMax[6]); - ui.radio8Widget->setMin(rcMin[7]); - ui.radio8Widget->setMax(rcMax[7]); - } -} -void RadioCalibrationConfig::showEvent(QShowEvent *event) -{ - Q_UNUSED(event); - guiUpdateTimer->start(100); -} -void RadioCalibrationConfig::hideEvent(QHideEvent *event) -{ - Q_UNUSED(event); - guiUpdateTimer->stop(); -} -void RadioCalibrationConfig::calibrateButtonClicked() -{ - if (!m_calibrationEnabled) - { - ui.calibrateButton->setText("End Calibration"); - QMessageBox::information(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and reciever are powered and connected\n\nClick OK to confirm"); - m_calibrationEnabled = true; - for (int i=0;i<8;i++) - { - rcMin[i] = 1500; - rcMax[i] = 1500; - } - ui.rollWidget->showMinMax(true); - ui.pitchWidget->showMinMax(true); - ui.yawWidget->showMinMax(true); - ui.radio5Widget->showMinMax(true); - ui.radio6Widget->showMinMax(true); - ui.radio7Widget->showMinMax(true); - ui.throttleWidget->showMinMax(true); - ui.radio8Widget->showMinMax(true); - QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches"); - } - else - { - ui.calibrateButton->setText("Calibrate"); - QMessageBox::information(0,"Trims","Ensure all sticks are centered and throttle is in the downmost position, click OK to continue"); - ///TODO: Set trims! - m_calibrationEnabled = false; - ui.rollWidget->showMinMax(false); - ui.pitchWidget->showMinMax(false); - ui.yawWidget->showMinMax(false); - ui.radio5Widget->showMinMax(false); - ui.radio6Widget->showMinMax(false); - ui.throttleWidget->showMinMax(false); - ui.radio7Widget->showMinMax(false); - ui.radio8Widget->showMinMax(false); - QString statusstr; - statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n"; - statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500\n\n"; - statusstr += "Channel\tMin\tCenter\tMax\n"; - statusstr += "--------------------\n"; - for (int i=0;i<8;i++) - { - statusstr += QString::number(i) + "\t" + QString::number(rcMin[i]) + "\t" + QString::number(rcValue[i]) + "\t" + QString::number(rcMax[i]) + "\n"; - } - QMessageBox::information(0,"Status",statusstr); - //Send calibrations. - QString minTpl("RC%1_MIN"); - QString maxTpl("RC%1_MAX"); - //QString trimTpl("RC%1_TRIM"); - - // Do not write the RC type, as these values depend on this - // active onboard parameter - - for (unsigned int i = 0; i < 8; ++i) - { - qDebug() << "SENDING MIN" << minTpl.arg(i+1) << rcMin[i]; - qDebug() << "SENDING MAX" << maxTpl.arg(i+1) << rcMax[i]; - m_uas->getParamManager()->setParameter(1, minTpl.arg(i+1), (float)rcMin[i]); - QGC::SLEEP::usleep(50000); - //m_uas->setParameter(0, trimTpl.arg(i+1), rcTrim[i]); - //QGC::SLEEP::usleep(50000); - m_uas->getParamManager()->setParameter(1, maxTpl.arg(i+1), (float)rcMax[i]); - QGC::SLEEP::usleep(50000); - } - ui.rollWidget->setMin(800); - ui.rollWidget->setMax(2200); - ui.pitchWidget->setMin(800); - ui.pitchWidget->setMax(2200); - ui.throttleWidget->setMin(800); - ui.throttleWidget->setMax(2200); - ui.yawWidget->setMin(800); - ui.yawWidget->setMax(2200); - ui.radio5Widget->setMin(800); - ui.radio5Widget->setMax(2200); - ui.radio6Widget->setMin(800); - ui.radio6Widget->setMax(2200); - ui.radio7Widget->setMin(800); - ui.radio7Widget->setMax(2200); - ui.radio8Widget->setMin(800); - ui.radio8Widget->setMax(2200); - - } -} diff --git a/src/ui/configuration/RadioCalibrationConfig.h b/src/ui/configuration/RadioCalibrationConfig.h deleted file mode 100644 index 00b90f8e20970fd1f2b3d7bf313149727f741758..0000000000000000000000000000000000000000 --- a/src/ui/configuration/RadioCalibrationConfig.h +++ /dev/null @@ -1,73 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2013 Michael Carpenter (malcom2073@gmail.com) - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Radio Calibration Configuration widget header. - * - * @author Michael Carpenter - * - */ - -#ifndef RADIOCALIBRATIONCONFIG_H -#define RADIOCALIBRATIONCONFIG_H - -#include -#include -#include -#include -#include "ui_RadioCalibrationConfig.h" -#include "UASManager.h" -#include "UASInterface.h" -#include "AP2ConfigWidget.h" -class RadioCalibrationConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit RadioCalibrationConfig(QWidget *parent = 0); - ~RadioCalibrationConfig(); -protected: - void showEvent(QShowEvent *event); - void hideEvent(QHideEvent *event); -private slots: - void activeUASSet(UASInterface *uas); - void remoteControlChannelRawChanged(int chan,float val); - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void guiUpdateTimerTick(); - void calibrateButtonClicked(); -private: - QList rcMin; - QList rcMax; - QList rcTrim; - QList rcValue; - //double rcMin[8]; - //double rcMax[8]; - //double rcTrim[8]; - //double rcValue[8]; - QTimer *guiUpdateTimer; - bool m_calibrationEnabled; - Ui::RadioCalibrationConfig ui; -}; - -#endif // RADIOCALIBRATIONCONFIG_H diff --git a/src/ui/configuration/RadioCalibrationConfig.ui b/src/ui/configuration/RadioCalibrationConfig.ui deleted file mode 100644 index ccf80621198ef28a53d60e967e397d0e811d5bb5..0000000000000000000000000000000000000000 --- a/src/ui/configuration/RadioCalibrationConfig.ui +++ /dev/null @@ -1,280 +0,0 @@ - - - RadioCalibrationConfig - - - - 0 - 0 - 771 - 389 - - - - Form - - - - - 10 - 10 - 171 - 31 - - - - <h2>Radio Calibration</h2> - - - false - - - - - - 10 - 50 - 716 - 300 - - - - - QLayout::SetMinAndMaxSize - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 50 - 200 - - - - - 50 - 200 - - - - - - - - Qt::Horizontal - - - - 250 - 20 - - - - - - - - - 50 - 200 - - - - - 50 - 200 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - 20 - 360 - 91 - 23 - - - - Calibrate - - - - - - QGCRadioChannelDisplay - QWidget -
ui/designer/QGCRadioChannelDisplay.h
- 1 -
-
- - -
diff --git a/src/ui/configuration/SonarConfig.cc b/src/ui/configuration/SonarConfig.cc deleted file mode 100644 index 2826804fbae9ff276605b62d24b357a04a7f8375..0000000000000000000000000000000000000000 --- a/src/ui/configuration/SonarConfig.cc +++ /dev/null @@ -1,74 +0,0 @@ -#include "SonarConfig.h" -#include - -SonarConfig::SonarConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - ui.sonarTypeComboBox->addItem("XL-EZ0 / XL-EZ4"); - ui.sonarTypeComboBox->addItem("LV-EZ0"); - ui.sonarTypeComboBox->addItem("XL-EZL0"); - ui.sonarTypeComboBox->addItem("HRLV"); - connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(checkBoxToggled(bool))); - connect(ui.sonarTypeComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(sonarTypeChanged(int))); - - initConnections(); -} - -SonarConfig::~SonarConfig() -{ -} -void SonarConfig::checkBoxToggled(bool enabled) -{ - if (enabled) - { - ui.sonarTypeComboBox->setEnabled(false); - } - if (!m_uas) - { - QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration")); - return; - } - m_uas->getParamManager()->setParameter(1,"SONAR_ENABLE",ui.enableCheckBox->isChecked() ? 1 : 0); -} -void SonarConfig::sonarTypeChanged(int index) -{ - Q_UNUSED(index); - - if (!m_uas) - { - QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration")); - return; - } - m_uas->getParamManager()->setParameter(1,"SONAR_TYPE",ui.sonarTypeComboBox->currentIndex()); -} - -void SonarConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (parameterName == "SONAR_ENABLE") - { - if (value.toInt() == 0) - { - //Disabled - disconnect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(checkBoxToggled(bool))); - ui.enableCheckBox->setChecked(false); - connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(checkBoxToggled(bool))); - ui.sonarTypeComboBox->setEnabled(false); - } - else - { - disconnect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(checkBoxToggled(bool))); - ui.enableCheckBox->setChecked(true); - connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(checkBoxToggled(bool))); - ui.sonarTypeComboBox->setEnabled(true); - } - } - else if (parameterName == "SONAR_TYPE") - { - disconnect(ui.sonarTypeComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(sonarTypeChanged(int))); - ui.sonarTypeComboBox->setCurrentIndex(value.toInt()); - connect(ui.sonarTypeComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(sonarTypeChanged(int))); - } -} diff --git a/src/ui/configuration/SonarConfig.h b/src/ui/configuration/SonarConfig.h deleted file mode 100644 index 825591a65294e37f5359675d715103031bf601c9..0000000000000000000000000000000000000000 --- a/src/ui/configuration/SonarConfig.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef SONARCONFIG_H -#define SONARCONFIG_H - -#include -#include "AP2ConfigWidget.h" -#include "ui_SonarConfig.h" - -class SonarConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit SonarConfig(QWidget *parent = 0); - ~SonarConfig(); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void checkBoxToggled(bool enabled); - void sonarTypeChanged(int index); -private: - Ui::SonarConfig ui; -}; - -#endif // SONARCONFIG_H diff --git a/src/ui/configuration/SonarConfig.ui b/src/ui/configuration/SonarConfig.ui deleted file mode 100644 index 7c40d028ce6c772db234b8972473c3ed906b7019..0000000000000000000000000000000000000000 --- a/src/ui/configuration/SonarConfig.ui +++ /dev/null @@ -1,79 +0,0 @@ - - - SonarConfig - - - - 0 - 0 - 651 - 432 - - - - Form - - - - - 20 - 20 - 131 - 31 - - - - <h2>Sonar</h2> - - - false - - - - - - 30 - 60 - 91 - 81 - - - - - - - :/files/images/devices/AC-0004-11-2.jpg - - - true - - - - - - 140 - 60 - 70 - 17 - - - - Enable - - - - - - 150 - 100 - 171 - 22 - - - - - - - - - diff --git a/src/ui/configuration/StandardParamConfig.cc b/src/ui/configuration/StandardParamConfig.cc deleted file mode 100644 index 509a109eea0d7df9c781bfcc451f647a43c7fd8a..0000000000000000000000000000000000000000 --- a/src/ui/configuration/StandardParamConfig.cc +++ /dev/null @@ -1,66 +0,0 @@ -#include "StandardParamConfig.h" -#include "ParamWidget.h" -StandardParamConfig::StandardParamConfig(QWidget *parent) : AP2ConfigWidget(parent) -{ - ui.setupUi(this); - initConnections(); -} -StandardParamConfig::~StandardParamConfig() -{ -} -void StandardParamConfig::addRange(QString title,QString description,QString param,double min,double max) -{ - ParamWidget *widget = new ParamWidget(param,ui.scrollAreaWidgetContents); - connect(widget,SIGNAL(doubleValueChanged(QString,double)),this,SLOT(doubleValueChanged(QString,double))); - connect(widget,SIGNAL(intValueChanged(QString,int)),this,SLOT(intValueChanged(QString,int))); - paramToWidgetMap[param] = widget; - widget->setupDouble(title + "(" + param + ")",description,0,min,max); - ui.verticalLayout->addWidget(widget); - widget->show(); -} - -void StandardParamConfig::addCombo(QString title,QString description,QString param,QList > valuelist) -{ - ParamWidget *widget = new ParamWidget(param,ui.scrollAreaWidgetContents); - connect(widget,SIGNAL(doubleValueChanged(QString,double)),this,SLOT(doubleValueChanged(QString,double))); - connect(widget,SIGNAL(intValueChanged(QString,int)),this,SLOT(intValueChanged(QString,int))); - paramToWidgetMap[param] = widget; - widget->setupCombo(title + "(" + param + ")",description,valuelist); - ui.verticalLayout->addWidget(widget); - widget->show(); -} -void StandardParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) -{ - Q_UNUSED(uas); - Q_UNUSED(component); - - if (paramToWidgetMap.contains(parameterName)) - { - if (value.type() == QVariant::Double) - { - paramToWidgetMap[parameterName]->setValue(value.toDouble()); - } - else - { - paramToWidgetMap[parameterName]->setValue(value.toInt()); - } - } -} -void StandardParamConfig::doubleValueChanged(QString param,double value) -{ - if (!m_uas) - { - this->showNullMAVErrorMessageBox(); - } - m_uas->getParamManager()->setParameter(1,param,value); -} - -void StandardParamConfig::intValueChanged(QString param,int value) -{ - if (!m_uas) - { - this->showNullMAVErrorMessageBox(); - } - m_uas->getParamManager()->setParameter(1,param,value); -} - diff --git a/src/ui/configuration/StandardParamConfig.h b/src/ui/configuration/StandardParamConfig.h deleted file mode 100644 index b098d7d05e1863b1ca98c5e0bd08bf86b7ec1d0a..0000000000000000000000000000000000000000 --- a/src/ui/configuration/StandardParamConfig.h +++ /dev/null @@ -1,26 +0,0 @@ -#ifndef STANDARDPARAMCONFIG_H -#define STANDARDPARAMCONFIG_H - -#include -#include "ui_StandardParamConfig.h" -#include "AP2ConfigWidget.h" -#include "ParamWidget.h" -class StandardParamConfig : public AP2ConfigWidget -{ - Q_OBJECT - -public: - explicit StandardParamConfig(QWidget *parent = 0); - ~StandardParamConfig(); - void addRange(QString title,QString description,QString param,double min,double max); - void addCombo(QString title,QString description,QString param,QList > valuelist); -private slots: - void parameterChanged(int uas, int component, QString parameterName, QVariant value); - void doubleValueChanged(QString param,double value); - void intValueChanged(QString param,int value); -private: - QMap paramToWidgetMap; - Ui::StandardParamConfig ui; -}; - -#endif // STANDARDPARAMCONFIG_H diff --git a/src/ui/configuration/StandardParamConfig.ui b/src/ui/configuration/StandardParamConfig.ui deleted file mode 100644 index 53a96d984792d7aa6198efe9bfb7f3864b57c523..0000000000000000000000000000000000000000 --- a/src/ui/configuration/StandardParamConfig.ui +++ /dev/null @@ -1,50 +0,0 @@ - - - StandardParamConfig - - - - 0 - 0 - 651 - 552 - - - - Form - - - - - - <h2>Standard Params</h2> - - - - - - - true - - - - - 0 - 0 - 631 - 505 - - - - - - - - - - - - - - - diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index 99969c492e3b936db1c66c657dda8edf2563a01c..eda68933c03b796f0cfb6ccc34b8cc41858030ec 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -6,7 +6,6 @@ #include "MAV2DIcon.h" #include "Waypoint2DIcon.h" #include "UASWaypointManager.h" -#include "ArduPilotMegaMAV.h" QGCMapWidget::QGCMapWidget(QWidget *parent) : mapcontrol::OPMapWidget(parent), @@ -56,11 +55,6 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : guidedaction->setText("Go To Here Alt (Guided Mode)"); connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered())); this->addAction(guidedaction); - // Point camera option - QAction *cameraaction = new QAction(this); - cameraaction->setText("Point Camera Here"); - connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered())); - this->addAction(cameraaction); // Set home location option QAction *sethomeaction = new QAction(this); sethomeaction->setText("Set Home Location Here"); @@ -111,21 +105,6 @@ bool QGCMapWidget::guidedAltActionTriggered() guidedActionTriggered(); return true; } -void QGCMapWidget::cameraActionTriggered() -{ - if (!uas) - { - QMessageBox::information(0,"Error","Please connect first"); - return; - } - ArduPilotMegaMAV *newmav = qobject_cast(this->uas); - if (newmav) - { - newmav->setMountConfigure(4,true,true,true); - internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y()); - newmav->setMountControl(pos.Lat(),pos.Lng(),100,true); - } -} /** * @brief QGCMapWidget::setHomeActionTriggered diff --git a/src/ui/map/QGCMapWidget.h b/src/ui/map/QGCMapWidget.h index 1550c7effc8ada58a56a1fa85ae843b74718ab25..d290476a7b830267a80a7b8897118c1b1bb2f4a3 100644 --- a/src/ui/map/QGCMapWidget.h +++ b/src/ui/map/QGCMapWidget.h @@ -45,8 +45,6 @@ signals: void waypointChanged(Waypoint* wp); public slots: - /** @brief Action triggered with point-camera action is selected from the context menu */ - void cameraActionTriggered(); /** @brief Action triggered when guided action is selected from the context menu */ void guidedActionTriggered(); /** @brief Action triggered when guided action is selected from the context menu, allows for altitude selection */ diff --git a/src/ui/px4_configuration/PX4Bootloader.cc b/src/ui/px4_configuration/PX4Bootloader.cc new file mode 100644 index 0000000000000000000000000000000000000000..51c6d3310b4ae9b85269879f4ac0a5b711a887f9 --- /dev/null +++ b/src/ui/px4_configuration/PX4Bootloader.cc @@ -0,0 +1,488 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief PX4 Bootloader Utility routines +/// @author Don Gagne + +#include "PX4Bootloader.h" + +#include +#include +#include +#include + +static const quint32 crctab[] = +{ + 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, + 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, + 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, + 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, + 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, + 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59, + 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f, + 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, + 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, + 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, + 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, + 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, + 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, + 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, + 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f, + 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad, + 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, + 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, + 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, + 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, + 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, + 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, + 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, + 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, + 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713, + 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, + 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, + 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, + 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, + 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, + 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, + 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d +}; + +static quint32 crc32(const uint8_t *src, unsigned len, unsigned state) +{ + for (unsigned i = 0; i < len; i++) { + state = crctab[(state ^ src[i]) & 0xff] ^ (state >> 8); + } + return state; +} + +const struct PX4Bootloader::serialPortErrorString PX4Bootloader::_rgSerialPortErrors[14] = { + { QSerialPort::NoError, "No error occurred." }, + { QSerialPort::DeviceNotFoundError, "An error occurred while attempting to open a non-existing device." }, + { QSerialPort::PermissionError, "An error occurred while attempting to open an already opened device by another process or a user not having enough permission and credentials to open." }, + { QSerialPort::OpenError, "An error occurred while attempting to open an already opened device in this object." }, + { QSerialPort::NotOpenError, "This error occurs when an operation is executed that can only be successfully performed if the device is open." }, + { QSerialPort::ParityError, "Parity error detected by the hardware while reading data." }, + { QSerialPort::FramingError, "Framing error detected by the hardware while reading data." }, + { QSerialPort::BreakConditionError, "Break condition detected by the hardware on the input line." }, + { QSerialPort::WriteError, "An I/O error occurred while writing the data." }, + { QSerialPort::ReadError, "An I/O error occurred while reading the data." }, + { QSerialPort::ResourceError, "An I/O error occurred when a resource becomes unavailable, e.g. when the device is unexpectedly removed from the system." }, + { QSerialPort::UnsupportedOperationError, "The requested device operation is not supported or prohibited by the running operating system." }, + { QSerialPort::TimeoutError, "A timeout error occurred." }, + { QSerialPort::UnknownError, "An unidentified error occurred." } +}; + +PX4Bootloader::PX4Bootloader(QObject *parent) : + QObject(parent) +{ + +} + +/// @brief Translate a QSerialPort::SerialPortError code into a string. +const char* PX4Bootloader::_serialPortErrorString(int error) +{ +Again: + for (size_t i=0; ibytesToWrite() > 50) { + int bump = 0; + bump++; + } + + qint64 bytesWritten = port->write((const char*)data, maxSize); + if (bytesWritten == -1) { + _errorString = tr("Write failed: %1").arg(port->errorString()); + qWarning() << _errorString; + return false; + } + if (bytesWritten != maxSize) { + _errorString = tr("Incorrect number of bytes returned for write: actual(%1) expected(%2)").arg(bytesWritten).arg(maxSize); + qWarning() << _errorString; + return false; + } + if (!port->waitForBytesWritten(1000)) { + _errorString = tr("Timeout waiting for write"); + qWarning() << _errorString; + return false; + } + + return true; +} + +bool PX4Bootloader::write(QSerialPort* port, const uint8_t byte) +{ + uint8_t buf[1] = { byte }; + return write(port, buf, 1); +} + +bool PX4Bootloader::read(QSerialPort* port, uint8_t* data, qint64 maxSize, bool warnOnError, int readTimeout) +{ + qint64 bytesToRead = 0; + + while (bytesToRead < maxSize) { + if (port->bytesAvailable() == 0) { + if (!port->waitForReadyRead(readTimeout)) { + _errorString = tr("Timeout waiting for byte to be available"); + if (warnOnError) { + qWarning() << _errorString; + } + return false; + } + Q_ASSERT(port->bytesAvailable() != 0); + } + + qint64 bytesRead; + bytesRead = port->read((char*)&data[bytesToRead], maxSize); + + if (bytesRead == -1) { + _errorString = tr("Read failed: Could not read 1 byte, error: %1").arg(port->errorString()); + if (warnOnError) { + qWarning() << _errorString; + } + return false; + } else { + Q_ASSERT(bytesRead != 0); + bytesToRead += bytesRead; + } + } + + return true; +} + +bool PX4Bootloader::getCommandResponse(QSerialPort* port, bool warnOnError, int responseTimeout) +{ + uint8_t response[2]; + + if (!read(port, response, 2, warnOnError, responseTimeout)) { + return false; + } + + // Make sure we get a good sync response + if (response[0] != PROTO_INSYNC) { + _errorString = tr("Invalid sync response: 0x%1 0x%2").arg(response[0], 2, 16, QLatin1Char('0')).arg(response[1], 2, 16, QLatin1Char('0')); + if (warnOnError) { + qWarning() << _errorString; + } + return false; + } else if (response[1] != PROTO_OK) { + QString responseCode = tr("Unknown response code"); + if (response[1] == PROTO_FAILED) { + responseCode = "PROTO_FAILED"; + } else if (response[1] == PROTO_INVALID) { + responseCode = "PROTO_INVALID"; + } + _errorString = tr("Command failed: 0x%1 (%2)").arg(response[1], 2, 16, QLatin1Char('0')).arg(responseCode); + if (warnOnError) { + qWarning() << _errorString; + } + return false; + } + + return true; +} + +bool PX4Bootloader::getBoardInfo(QSerialPort* port, uint8_t param, uint32_t& value) +{ + uint8_t buf[3] = { PROTO_GET_DEVICE, param, PROTO_EOC }; + + if (!write(port, buf, sizeof(buf))) { + return false; + } + if (!read(port, (uint8_t*)&value, sizeof(value), warnOnError)) { + return false; + } + return getCommandResponse(port, warnOnError); +} + +bool PX4Bootloader::sendCommand(QSerialPort* port, const uint8_t cmd, bool warnOnError, int responseTimeout) +{ + uint8_t buf[2] = { cmd, PROTO_EOC }; + + if (!write(port, buf, 2)) { + return false; + } + return getCommandResponse(port, warnOnError, responseTimeout); +} + +bool PX4Bootloader::erase(QSerialPort* port) +{ + // Erase is slow, need larger timeout + if (!sendCommand(port, PROTO_CHIP_ERASE, warnOnError, _eraseTimeout)) { + _errorString = tr("Board erase failed: %1").arg(_errorString); + qWarning() << _errorString; + return false; + } + + return true; +} + +bool PX4Bootloader::program(QSerialPort* port, const QString& firmwareFilename) +{ + QFile firmwareFile(firmwareFilename); + if (!firmwareFile.open(QIODevice::ReadOnly)) { + _errorString = tr("Unable to open firmware file %1: %2").arg(firmwareFilename).arg(firmwareFile.errorString()); + qWarning() << _errorString; + return false; + } + uint32_t imageSize = (uint32_t)firmwareFile.size(); + + uint8_t imageBuf[PROG_MULTI_MAX]; + uint32_t bytesSent = 0; + _imageCRC = 0; + + Q_ASSERT(PROG_MULTI_MAX <= 0x8F); + + while (bytesSent < imageSize) { + int bytesToSend = imageSize - bytesSent; + if (bytesToSend > (int)sizeof(imageBuf)) { + bytesToSend = (int)sizeof(imageBuf); + } + + Q_ASSERT((bytesToSend % 4) == 0); + + int bytesRead = firmwareFile.read((char *)imageBuf, bytesToSend); + if (bytesRead == -1 || bytesRead != bytesToSend) { + _errorString = tr("Read failed: %1").arg(firmwareFile.errorString()); + qWarning() << _errorString; + return false; + } + + Q_ASSERT(bytesToSend <= 0x8F); + + if (!write(port, PROTO_PROG_MULTI) || + !write(port, (uint8_t)bytesToSend) || + !write(port, imageBuf, bytesToSend) || + !write(port, PROTO_EOC) || + !getCommandResponse(port, warnOnError)) { + _errorString = tr("Flash failed: %1").arg(_errorString); + qWarning() << _errorString; + return false; + } + + bytesSent += bytesToSend; + + // Calculate the CRC now so we can test it after the board is flashed. + _imageCRC = crc32((uint8_t *)imageBuf, bytesToSend, _imageCRC); + + emit updateProgramProgress(bytesSent, imageSize); + } + firmwareFile.close(); + + // We calculate the CRC using the entire flash size, filling the remainder with 0xFF. + while (bytesSent < _boardFlashSize) { + const uint8_t fill = 0xFF; + _imageCRC = crc32(&fill, 1, _imageCRC); + bytesSent++; + } + + return true; +} + +bool PX4Bootloader::verify(QSerialPort* port, const QString firmwareFilename) +{ + bool ret; + + if (_bootloaderVersion <= 2) { + ret = _bootloaderVerifyRev2(port, firmwareFilename); + } else { + ret = _bootloaderVerifyRev3(port); + } + + sendBootloaderReboot(port); + + return ret; +} + +/// @brief Verify the flash on bootloader version 2 by reading it back and comparing it against +/// the original firmware file. +bool PX4Bootloader::_bootloaderVerifyRev2(QSerialPort* port, const QString firmwareFilename) +{ + QFile firmwareFile(firmwareFilename); + if (!firmwareFile.open(QIODevice::ReadOnly)) { + _errorString = tr("Unable to open firmware file %1: %2").arg(firmwareFilename).arg(firmwareFile.errorString()); + qWarning() << _errorString; + return false; + } + uint32_t imageSize = (uint32_t)firmwareFile.size(); + + if (!sendCommand(port, PROTO_CHIP_VERIFY, warnOnError)) { + return false; + } + + uint8_t fileBuf[READ_MULTI_MAX]; + uint8_t flashBuf[READ_MULTI_MAX]; + uint32_t bytesVerified = 0; + + Q_ASSERT(PROG_MULTI_MAX <= 0x8F); + + while (bytesVerified < imageSize) { + int bytesToRead = imageSize - bytesVerified; + if (bytesToRead > (int)sizeof(fileBuf)) { + bytesToRead = (int)sizeof(fileBuf); + } + + Q_ASSERT((bytesToRead % 4) == 0); + + int bytesRead = firmwareFile.read((char *)fileBuf, bytesToRead); + if (bytesRead == -1 || bytesRead != bytesToRead) { + _errorString = tr("Read failed: %1").arg(firmwareFile.errorString()); + qWarning() << _errorString; + return false; + } + + Q_ASSERT(bytesToRead <= 0x8F); + + if (!write(port, PROTO_READ_MULTI) || + !write(port, (uint8_t)bytesToRead) || + !write(port, PROTO_EOC) || + !read(port, flashBuf, sizeof(flashBuf), warnOnError) || + !getCommandResponse(port, warnOnError)) { + return false; + } + + for (int i=0; iisOpen()); + + port->setPortName(portName); + port->setBaudRate(QSerialPort::Baud115200); + port->setDataBits(QSerialPort::Data8); + port->setParity(QSerialPort::NoParity); + port->setStopBits(QSerialPort::OneStop); + port->setFlowControl(QSerialPort::NoFlowControl); + + if (!port->open(QIODevice::ReadWrite)) { + _errorString = tr("Open failed on port %1: %2").arg(portName).arg(_serialPortErrorString(port->error())); + qWarning() << _errorString; + return false; + } + + return true; +} + +bool PX4Bootloader::sync(QSerialPort* port) +{ + // Drain out any remaining input or output from the port + if (!port->clear()) { + _errorString = tr("Unable to clear port"); + qWarning() << _errorString; + return false; + } + + // Send sync command + return sendCommand(port, PROTO_GET_SYNC, noWarnOnError); +} + +bool PX4Bootloader::getBoardInfo(QSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize) +{ + + if (!getBoardInfo(port, INFO_BL_REV, _bootloaderVersion)) { + goto Error; + } + if (_bootloaderVersion < BL_REV_MIN || _bootloaderVersion > BL_REV_MAX) { + _errorString = tr("Found unsupported bootloader version: %1").arg(_bootloaderVersion); + qWarning() << _errorString; + goto Error; + } + + if (!getBoardInfo(port, INFO_BOARD_ID, _boardID)) { + goto Error; + } + if (_boardID != _boardIDPX4Flow && _boardID != _boardIDPX4FMUV1 && _boardID != _boardIDPX4FMUV2) { + _errorString = tr("Unsupported board: %1").arg(_boardID); + qWarning() << _errorString; + goto Error; + } + + if (!getBoardInfo(port, INFO_FLASH_SIZE, _boardFlashSize)) { + qWarning() << _errorString; + goto Error; + } + + bootloaderVersion = _bootloaderVersion; + boardID = _boardID; + flashSize = _boardFlashSize; + + return true; + +Error: + return false; +} + +bool PX4Bootloader::sendBootloaderReboot(QSerialPort* port) +{ + return write(port, PROTO_BOOT) && write(port, PROTO_EOC); +} diff --git a/src/ui/px4_configuration/PX4Bootloader.h b/src/ui/px4_configuration/PX4Bootloader.h new file mode 100644 index 0000000000000000000000000000000000000000..566bc001832c1e2c2ca7d12d7cc14a754f37a318 --- /dev/null +++ b/src/ui/px4_configuration/PX4Bootloader.h @@ -0,0 +1,178 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief PX4 Bootloader Utility routines +/// @author Don Gagne + +#ifndef PX4Bootloader_H +#define PX4Bootloader_H + +#include + +#include + +/// @brief This class is used to communicate with the Bootloader. +class PX4Bootloader : public QObject +{ + Q_OBJECT + +public: + explicit PX4Bootloader(QObject *parent = 0); + + /// @brief Returns the error message associated with the last failed call to one of the bootloader + /// utility routine below. + QString errorString(void) { return _errorString; } + + static const bool warnOnError = true; ///< call qWarning to log error message on error + static const bool noWarnOnError = false; ///< Don't call qWarning on error + + /// @brief Write a byte to the port + /// @param port Port to write to + /// @param data Bytes to write + /// @param maxSize Number of bytes to write + /// @return true: success + bool write(QSerialPort* port, const uint8_t* data, qint64 maxSize); + bool write(QSerialPort* port, const uint8_t byte); + + /// @brief Read a set of bytes from the port + /// @param data Read bytes into this buffer + /// @param maxSize Number of bytes to read + /// @param warnOnError true: Log error using qWarning + /// @param readTimeout Msecs to wait for bytes to become available on port + bool read(QSerialPort* port, uint8_t* data, qint64 maxSize, bool warnOnError, int readTimeout = _readTimout); + + /// @brief Read a PROTO_SYNC command response from the bootloader + /// @param responseTimeout Msecs to wait for response bytes to become available on port + bool getCommandResponse(QSerialPort* port, bool warnOnError, const int responseTimeout = _responseTimeout); + + /// @brief Send a PROTO_GET_DEVICE command to retrieve a value from the bootloader + /// @param param Value to retrieve using INFO_BOARD_* enums + /// @param value Returned value + bool getBoardInfo(QSerialPort* port, uint8_t param, uint32_t& value); + + /// @brief Send a command to the bootloader + /// @param cmd Command to send using PROTO_* enums + /// @return true: Command sent and valid sync response returned + bool sendCommand(QSerialPort* port, uint8_t cmd, bool warnOnError, int responseTimeout = _responseTimeout); + + /// @brief Program the board with the specified firmware + bool program(QSerialPort* port, const QString& firmwareFilename); + + /// @brief Verify the board flash. How it works depend on bootloader rev + /// Rev 2: Read the flash back and compare it against the firmware file + /// Rev 3: Compare CRCs for flash and file + bool verify(QSerialPort* port, const QString firmwareFilename); + + /// @brief Read a PROTO_SYNC response from the bootloader + /// @return true: Valid sync response was received + bool sync(QSerialPort* port); + + /// @brief Retrieve a set of board info from the bootloader + /// @param bootloaderVersion Returned INFO_BL_REV + /// @param boardID Returned INFO_BOARD_ID + /// @param flashSize Returned INFO_FLASH_SIZE + bool getBoardInfo(QSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize); + + /// @brief Opens a port to the bootloader + bool open(QSerialPort* port, const QString portName); + + /// @brief Sends a PROTO_REBOOT command to the bootloader + bool sendBootloaderReboot(QSerialPort* port); + + /// @brief Sends a PROTO_ERASE command to the bootlader + bool erase(QSerialPort* port); + +signals: + /// @brief Signals progress indicator for long running bootloader utility routines + void updateProgramProgress(int curr, int total); + +private: + enum { + // protocol bytes + PROTO_INSYNC = 0x12, ///< 'in sync' byte sent before status + PROTO_EOC = 0x20, ///< end of command + + // Reply bytes + PROTO_OK = 0x10, ///< INSYNC/OK - 'ok' response + PROTO_FAILED = 0x11, ///< INSYNC/FAILED - 'fail' response + PROTO_INVALID = 0x13, ///< INSYNC/INVALID - 'invalid' response for bad commands + + // Command bytes + PROTO_GET_SYNC = 0x21, ///< NOP for re-establishing sync + PROTO_GET_DEVICE = 0x22, ///< get device ID bytes + PROTO_CHIP_ERASE = 0x23, ///< erase program area and reset program address + PROTO_PROG_MULTI = 0x27, ///< write bytes at program address and increment + PROTO_GET_CRC = 0x29, ///< compute & return a CRC + PROTO_BOOT = 0x30, ///< boot the application + + // Command bytes - Rev 2 boootloader only + PROTO_CHIP_VERIFY = 0x24, ///< begin verify mode + PROTO_READ_MULTI = 0x28, ///< read bytes at programm address and increment + + INFO_BL_REV = 1, ///< bootloader protocol revision + BL_REV_MIN = 2, ///< Minimum supported bootlader protocol + BL_REV_MAX = 4, ///< Maximum supported bootloader protocol + INFO_BOARD_ID = 2, ///< board type + INFO_BOARD_REV = 3, ///< board revision + INFO_FLASH_SIZE = 4, ///< max firmware size in bytes + + PROG_MULTI_MAX = 32, ///< write size for PROTO_PROG_MULTI, must be multiple of 4 + READ_MULTI_MAX = 64 ///< read size for PROTO_READ_MULTI, must be multiple of 4 + }; + + struct serialPortErrorString { + int error; + const char* errorString; + }; + + bool _findBootloader(void); + bool _downloadFirmware(void); + bool _bootloaderVerifyRev2(QSerialPort* port, const QString firmwareFilename); + bool _bootloaderVerifyRev3(QSerialPort* port); + + const char* _serialPortErrorString(int error); + + static const int _boardIDPX4FMUV1 = 5; ///< Board ID for PX4 V1 board + static const int _boardIDPX4FMUV2 = 9; ///< Board ID for PX4 V2 board + static const int _boardIDPX4Flow = 6; ///< Board ID for PX4 Floaw board + + uint32_t _boardID; ///< board id for currently connected board + uint32_t _boardFlashSize; ///< flash size for currently connected board + uint32_t _imageCRC; ///< CRC for image in currently selected firmware file + uint32_t _bootloaderVersion; ///< Bootloader version + + QString _firmwareFilename; ///< Currently selected firmware file to flash + + QString _errorString; ///< Last error + + static const struct serialPortErrorString _rgSerialPortErrors[14]; ///< Translation of QSerialPort::SerialPortError into string + + static const int _eraseTimeout = 20000; ///< Msecs to wait for response from erase command + static const int _rebootTimeout = 10000; ///< Msecs to wait for reboot command to cause serial port to disconnect + static const int _verifyTimeout = 5000; ///< Msecs to wait for response to PROTO_GET_CRC command + static const int _readTimout = 2000; ///< Msecs to wait for read bytes to become avilable + static const int _responseTimeout = 2000; ///< Msecs to wait for command response bytes +}; + +#endif // PX4FirmwareUpgrade_H diff --git a/src/ui/px4_configuration/PX4FirmwareUpgrade.cc b/src/ui/px4_configuration/PX4FirmwareUpgrade.cc new file mode 100644 index 0000000000000000000000000000000000000000..70c1e067cedcde58be55ae3dc6ec3076df6310a7 --- /dev/null +++ b/src/ui/px4_configuration/PX4FirmwareUpgrade.cc @@ -0,0 +1,815 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief PX4 Firmware Upgrade UI +/// @author Don Gagne + +#include "PX4FirmwareUpgrade.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +/// @Brief Constructs a new PX4FirmwareUpgrade Widget. This widget is used within the PX4VehicleConfig set of screens. +PX4FirmwareUpgrade::PX4FirmwareUpgrade(QWidget *parent) : + QWidget(parent), + _upgradeState(upgradeStateBegin), + _downloadManager(NULL), + _downloadNetworkReply(NULL) +{ + _ui = new Ui::PX4FirmwareUpgrade; + _ui->setupUi(this); + + _threadController = new PX4FirmwareUpgradeThreadController(this); + Q_CHECK_PTR(_threadController); + + // Connect standard ui elements + connect(_ui->tryAgain, &QPushButton::clicked, this, &PX4FirmwareUpgrade::_tryAgainButton); + connect(_ui->cancel, &QPushButton::clicked, this, &PX4FirmwareUpgrade::_cancelButton); + connect(_ui->next, &QPushButton::clicked, this, &PX4FirmwareUpgrade::_nextButton); + connect(_ui->firmwareCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(_firmwareSelected(int))); + + connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBoard, this, &PX4FirmwareUpgrade::_foundBoard); + connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBootloader, this, &PX4FirmwareUpgrade::_foundBootloader); + connect(_threadController, &PX4FirmwareUpgradeThreadController::bootloaderSyncFailed, this, &PX4FirmwareUpgrade::_bootloaderSyncFailed); + connect(_threadController, &PX4FirmwareUpgradeThreadController::error, this, &PX4FirmwareUpgrade::_error); + connect(_threadController, &PX4FirmwareUpgradeThreadController::complete, this, &PX4FirmwareUpgrade::_complete); + connect(_threadController, &PX4FirmwareUpgradeThreadController::findTimeout, this, &PX4FirmwareUpgrade::_findTimeout); + connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &PX4FirmwareUpgrade::_updateProgress); + + connect(&_eraseTimer, &QTimer::timeout, this, &PX4FirmwareUpgrade::_eraseProgressTick); + + _setupState(upgradeStateBegin); +} + +PX4FirmwareUpgrade::~PX4FirmwareUpgrade() +{ +} + +/// @brief Returns the state machine entry for the specified state. +const PX4FirmwareUpgrade::stateMachineEntry* PX4FirmwareUpgrade::_getStateMachineEntry(enum PX4FirmwareUpgrade::upgradeStates state) +{ + static const char* msgBegin = "If you are currently connected to your Pixhawk board via QGroundControl, you must 'Disconnect' from the board. " + "If your board is connected via USB, you must unplug the USB cable.\n\n" + "Click 'Next' when these two steps are complete to begin upgrading."; + static const char* msgBoardSearch = "Plug in your board via USB now..."; + static const char* msgBoardNotFound = "Unable to detect your board. If the board is currently connected via USB. Disconnect it, and click 'Try Again'."; + static const char* msgBootloaderSearch = "Searching for Bootloader..."; + static const char* msgBootloaderNotFound = "Unable to connect to Bootloader. If the board is currently connected via USB. Disconnect it, and click 'Try Again'."; + static const char* msgBootloaderError = "An error occured while communicating with the Bootloader."; + static const char* msgFirmwareSelect = "Please select the firmware you would like to upload to the board from the dropdown to the right."; + static const char* msgFirmwareDownloading = "Firmware downloading..."; + static const char* msgFirmwareDownloadFailed = "Firmware download failed"; + static const char* msgFirmwareBoardErasing = "Erasing old firmware from board..."; + static const char* msgFirmwareBoardEraseFailed = "Board erase failed."; + static const char* msgFirmwareBoardFlashing = "Flashing new firmware onto board..."; + static const char* msgFirmwareBoardFlashError = "A failure has occured while flashing the new firmware to your board. " + "This has left the board in an inconsistent state. " + "You should click 'Try Again' to attempt the upgrade process again."; + static const char* msgFirmwareBoardVerifying = "Verifying firmware on board..."; + static const char* msgFirmwareBoardVerifyError = "Verification of flash memory on board failed. " + "This has left the board in an inconsistent state. " + "You should click 'Try Again' to attempt the upgrade process again."; + static const char* msgFirmwareBoardUpgraded = "Your board has been upgraded successfully.\n\nYou can now connect to your board via QGroundControl\n\nClick 'Try Again' to do another upgrade."; + + static const stateMachineEntry rgStateMachine[] = { + //State Next command Cancel command Try Again command State Text + { upgradeStateBegin, &PX4FirmwareUpgrade::_findBoard, NULL, NULL, msgBegin }, + { upgradeStateBoardSearch, NULL, &PX4FirmwareUpgrade::_cancelFind, NULL, msgBoardSearch }, + { upgradeStateBoardNotFound, NULL, &PX4FirmwareUpgrade::_cancel, &PX4FirmwareUpgrade::_findBoard, msgBoardNotFound }, + { upgradeStateBootloaderSearch, NULL, &PX4FirmwareUpgrade::_cancelFind, NULL, msgBootloaderSearch }, + { upgradeStateBootloaderNotFound, NULL, &PX4FirmwareUpgrade::_cancel, &PX4FirmwareUpgrade::_restart, msgBootloaderNotFound }, + { upgradeStateBootloaderError, NULL, &PX4FirmwareUpgrade::_cancel, NULL, msgBootloaderError }, + { upgradeStateFirmwareSelect, &PX4FirmwareUpgrade::_getFirmwareFile, &PX4FirmwareUpgrade::_cancel, NULL, msgFirmwareSelect }, + { upgradeStateFirmwareDownloading, NULL, &PX4FirmwareUpgrade::_cancelDownload, NULL, msgFirmwareDownloading }, + { upgradeStateDownloadFailed, NULL, NULL, &PX4FirmwareUpgrade::_restart, msgFirmwareDownloadFailed }, + { upgradeStateErasing, NULL, NULL, NULL, msgFirmwareBoardErasing }, + { upgradeStateEraseError, NULL, &PX4FirmwareUpgrade::_cancel, NULL, msgFirmwareBoardEraseFailed }, + { upgradeStateFlashing, NULL, NULL, NULL, msgFirmwareBoardFlashing }, + { upgradeStateFlashError, NULL, NULL, &PX4FirmwareUpgrade::_restart, msgFirmwareBoardFlashError }, + { upgradeStateVerifying, NULL, NULL, NULL, msgFirmwareBoardVerifying }, + { upgradeStateVerifyError, NULL, NULL, &PX4FirmwareUpgrade::_restart, msgFirmwareBoardVerifyError }, + { upgradeStateBoardUpgraded, NULL, NULL, &PX4FirmwareUpgrade::_restart, msgFirmwareBoardUpgraded }, + }; + + const stateMachineEntry* entry = &rgStateMachine[state]; + + // Validate that our state array has not gotten out of sync + for (size_t i=0; itryAgain->setEnabled(stateMachine->tryAgain != NULL); + _ui->skip->setEnabled(false); + _ui->cancel->setEnabled(stateMachine->cancel != NULL); + _ui->next->setEnabled(stateMachine->next != NULL); + + _ui->statusLog->setText(stateMachine->msg); + + if (_upgradeState == upgradeStateDownloadFailed) { + // Bootloader is still open, reboot to close and heopfully get back to FMU + _threadController->sendBootloaderReboot(); + } + + _updateIndicatorUI(); +} + +/// @brief Updates the Indicator UI which is to the right of the Wizard area to match the current +/// upgrade state. +void PX4FirmwareUpgrade::_updateIndicatorUI(void) +{ + if (_upgradeState == upgradeStateBegin) { + // Reset to intial state. All check boxes unchecked, all additional information hidden. + + _ui->statusLabel->clear(); + + _ui->progressBar->setValue(0); + _ui->progressBar->setTextVisible(false); + + _ui->boardFoundCheck->setCheckState(Qt::Unchecked); + _ui->port->setVisible(false); + _ui->description->setVisible(false); + + _ui->bootloaderFoundCheck->setCheckState(Qt::Unchecked); + _ui->bootloaderVersion->setVisible(false); + _ui->boardID->setVisible(false); + _ui->icon->setVisible(false); + + _ui->firmwareCombo->setVisible(false); + _ui->firmwareCombo->setEnabled(true); + + _ui->selectFirmwareCheck->setCheckState(Qt::Unchecked); + _ui->firmwareDownloadedCheck->setCheckState(Qt::Unchecked); + _ui->boardUpgradedCheck->setCheckState(Qt::Unchecked); + + } else if (_upgradeState == upgradeStateBootloaderSearch){ + // We have found the board + + _ui->statusLabel->clear(); + + _ui->progressBar->setValue(0); + + _ui->boardFoundCheck->setCheckState(Qt::Checked); + + _ui->port->setText("Port: " + _portName); + _ui->description->setText("Name: " +_portDescription); + + _ui->port->setVisible(true); + _ui->description->setVisible(true); + + } else if (_upgradeState == upgradeStateFirmwareSelect) { + // We've found the bootloader and need to set up firmware selection + + _ui->statusLabel->clear(); + + _ui->progressBar->setValue(0); + + _ui->bootloaderFoundCheck->setCheckState(Qt::Checked); + + + _ui->bootloaderVersion->setText(QString("Version: %1").arg(_bootloaderVersion)); + _ui->boardID->setText(QString("Board ID: %1").arg(_boardID)); + _setBoardIcon(_boardID); + _setFirmwareCombo(_boardID); + + _ui->bootloaderVersion->setVisible(true); + _ui->boardID->setVisible(true); + _ui->icon->setVisible(true); + _ui->firmwareCombo->setVisible(true); + _ui->firmwareCombo->setEnabled(true); + _ui->firmwareCombo->setCurrentIndex(0); + + } else if (_upgradeState == upgradeStateFirmwareDownloading) { + + _ui->statusLabel->clear(); + _ui->selectFirmwareCheck->setCheckState(Qt::Checked); + _ui->firmwareCombo->setEnabled(false); + + } else if (_upgradeState == upgradeStateFlashing) { + + _ui->statusLabel->clear(); + _ui->progressBar->setValue(0); + _ui->firmwareDownloadedCheck->setCheckState(Qt::Checked); + + } else if (_upgradeState == upgradeStateBoardUpgraded) { + + _ui->statusLabel->clear(); + _ui->progressBar->setValue(0); + _ui->boardUpgradedCheck->setCheckState((_upgradeState >= upgradeStateBoardUpgraded) ? Qt::Checked : Qt::Unchecked); + + } +} + +/// @brief Responds to a click on the Next Button calling the appropriate method as specified by the state machine. +void PX4FirmwareUpgrade::_nextButton(void) +{ + const stateMachineEntry* stateMachine = _getStateMachineEntry(_upgradeState); + + Q_ASSERT(stateMachine->next != NULL); + + (this->*stateMachine->next)(); +} + + +/// @brief Responds to a click on the Cancel Button calling the appropriate method as specified by the state machine. +void PX4FirmwareUpgrade::_cancelButton(void) +{ + const stateMachineEntry* stateMachine = _getStateMachineEntry(_upgradeState); + + Q_ASSERT(stateMachine->cancel != NULL); + + (this->*stateMachine->cancel)(); +} + +/// @brief Responds to a click on the Try Again Button calling the appropriate method as specified by the state machine. +void PX4FirmwareUpgrade::_tryAgainButton(void) +{ + const stateMachineEntry* stateMachine = _getStateMachineEntry(_upgradeState); + + Q_ASSERT(stateMachine->tryAgain != NULL); + + (this->*stateMachine->tryAgain)(); +} + +/// @brief Cancels a findBoard or findBootloader operation. +void PX4FirmwareUpgrade::_cancelFind(void) +{ + _threadController->cancelFind(); +} + +/// @brief Cancels the current state and returns to the begin start +void PX4FirmwareUpgrade::_cancel(void) +{ + _setupState(upgradeStateBegin); +} + +/// @brief Begins the process or searching for the board +void PX4FirmwareUpgrade::_findBoard(void) +{ + _setupState(upgradeStateBoardSearch); + _threadController->findBoard(_findBoardTimeoutMsec); +} + +/// @brief Called when board has been found by the findBoard process +void PX4FirmwareUpgrade::_foundBoard(const QString portName, QString portDescription) +{ + _portName = portName; + _portDescription = portDescription; + _setupState(upgradeStateBootloaderSearch); + _findBootloader(); +} + +/// @brief Begins the findBootloader process to connect to the bootloader +void PX4FirmwareUpgrade::_findBootloader(void) +{ + _setupState(upgradeStateBootloaderSearch); + _threadController->findBootloader(_portName, _findBootloaderTimeoutMsec); +} + +/// @brief Called when the bootloader is connected to by the findBootloader process. Moves the state machine +/// to the next step. +void PX4FirmwareUpgrade::_foundBootloader(int bootloaderVersion, int boardID, int flashSize) +{ + _bootloaderVersion = bootloaderVersion; + _boardID = boardID; + _boardFlashSize = flashSize; + _setupState(upgradeStateFirmwareSelect); +} + +/// @brief Called when the findBootloader process is unable to sync to the bootloader. Moves the state +/// machine to the appropriate error state. +void PX4FirmwareUpgrade::_bootloaderSyncFailed(void) +{ + if (_upgradeState == upgradeStateBootloaderSearch) { + // We can connect to the board, but we still can't talk to the bootloader. + qDebug() << "Bootloader sync failed"; + _setupState(upgradeStateBootloaderNotFound); + } else { + Q_ASSERT(false); + } + +} + +/// @brief Called when the findBoard or findBootloader process times out. Moves the state machine to the +/// appropriate error state. +void PX4FirmwareUpgrade::_findTimeout(void) +{ + if (_upgradeState == upgradeStateBoardSearch) { + qDebug() << "Timeout on board search"; + _setupState(upgradeStateBoardNotFound); + } else if (_upgradeState == upgradeStateBootloaderSearch) { + qDebug() << "Timeout on bootloader search"; + _setupState(upgradeStateBoardNotFound); + } else { + Q_ASSERT(false); + } +} + +/// @brief Sets the board image into the icon label according to the board id. +void PX4FirmwareUpgrade::_setBoardIcon(int boardID) +{ + QString imageFile; + + switch (boardID) { + case _boardIDPX4FMUV1: + imageFile = ":/files/images/px4/boards/px4fmu_1.x.png"; + break; + + case _boardIDPX4Flow: + imageFile = ":/files/images/px4/boards/px4flow_1.x.png"; + break; + + case _boardIDPX4FMUV2: + imageFile = ":/files/images/px4/boards/px4fmu_2.x.png"; + break; + } + + if (!imageFile.isEmpty()) { + bool success = _boardIcon.load(imageFile); + Q_ASSERT(success); + Q_UNUSED(success); + + int w = _ui->icon->width(); + int h = _ui->icon->height(); + + _ui->icon->setPixmap(_boardIcon.scaled(w, h, Qt::KeepAspectRatio)); + } +} + +/// @brief Sets up the selections in the firmware combox box associated with the specified +/// board id. +void PX4FirmwareUpgrade::_setFirmwareCombo(int boardID) +{ + _ui->firmwareCombo->clear(); + + static const char* rgPX4FMUV1Firmware[3] = + { + "http://px4.oznet.ch/stable/px4fmu-v1_default.px4", + "http://px4.oznet.ch/beta/px4fmu-v1_default.px4", + "http://px4.oznet.ch/continuous/px4fmu-v1_default.px4" + }; + + static const char* rgPX4FMUV2Firmware[3] = + { + "http://px4.oznet.ch/stable/px4fmu-v2_default.px4", + "http://px4.oznet.ch/beta/px4fmu-v2_default.px4", + "http://px4.oznet.ch/continuous/px4fmu-v2_default.px4" + }; + + static const char* rgPX4FlowFirmware[3] = + { + "http://px4.oznet.ch/stable/px4flow.px4", + "http://px4.oznet.ch/beta/px4flow.px4", + "http://px4.oznet.ch/continuous/px4flow.px4" + }; + + const char** prgFirmware; + switch (boardID) { + case _boardIDPX4FMUV1: + prgFirmware = rgPX4FMUV1Firmware; + break; + + case _boardIDPX4Flow: + prgFirmware = rgPX4FlowFirmware; + break; + + case _boardIDPX4FMUV2: + prgFirmware = rgPX4FMUV2Firmware; + break; + + default: + prgFirmware = NULL; + break; + } + + if (prgFirmware) { + _ui->firmwareCombo->addItem(tr("Standard Version (stable)"), prgFirmware[0]); + _ui->firmwareCombo->addItem(tr("Beta Testing (beta)"), prgFirmware[1]); + _ui->firmwareCombo->addItem(tr("Developer Build (master)"), prgFirmware[2]); + } + _ui->firmwareCombo->addItem(tr("Custom firmware file..."), "selectfile"); +} + +/// @brief Called when the selection in the firmware combo box changes. Updates the wizard +/// text appropriately with licensing and possibly warning information. +void PX4FirmwareUpgrade::_firmwareSelected(int index) +{ +#define SELECT_FIRMWARE_LICENSE "By clicking Next you agree to the terms and disclaimer of the BSD open source license, as redistributed with the source code." + + if (_upgradeState == upgradeStateFirmwareSelect) { + switch (index) { + case 0: + case 3: + _ui->statusLog->setText(tr(SELECT_FIRMWARE_LICENSE)); + break; + + case 1: + _ui->statusLog->setText(tr("WARNING: BETA FIRMWARE\n" + "This firmware version is ONLY intended for beta testers. " + "Although it has received FLIGHT TESTING, it represents actively changed code. Do NOT use for normal operation.\n\n" + SELECT_FIRMWARE_LICENSE)); + break; + + case 2: + _ui->statusLog->setText(tr("WARNING: CONTINUOUS BUILD FIRMWARE\n" + "This firmware has NOT BEEN FLIGHT TESTED. " + "It is only intended for DEVELOPERS. Run bench tests without props first. " + "Do NOT fly this without addional safety precautions. Follow the mailing " + "list actively when using it.\n\n" + SELECT_FIRMWARE_LICENSE)); + break; + } + _ui->next->setEnabled(!_ui->firmwareCombo->itemData(index).toString().isEmpty()); + } +} + +/// @brief Prompts the user to select a firmware file if needed and moves the state machine to the +/// download firmware state. +void PX4FirmwareUpgrade::_getFirmwareFile(void) +{ + int index = _ui->firmwareCombo->currentIndex(); + _firmwareFilename = _ui->firmwareCombo->itemData(index).toString(); + Q_ASSERT(!_firmwareFilename.isEmpty()); + if (_firmwareFilename == "selectfile") { + _firmwareFilename = QFileDialog::getOpenFileName(this, + tr("Select Firmware File"), // Dialog title + QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation), // Initial directory + tr("Firmware Files (*.px4 *.bin)")); // File filter + + } + if (!_firmwareFilename.isEmpty()) { + _downloadFirmware(); + } +} + +/// @brief Begins the process of downloading the selected firmware file. +void PX4FirmwareUpgrade::_downloadFirmware(void) +{ + // Split out filename from path + Q_ASSERT(!_firmwareFilename.isEmpty()); + QString firmwareFilename = QFileInfo(_firmwareFilename).fileName(); + Q_ASSERT(!firmwareFilename.isEmpty()); + + // Determine location to download file to + QString downloadFile = QStandardPaths::writableLocation(QStandardPaths::TempLocation); + if (downloadFile.isEmpty()) { + downloadFile = QStandardPaths::writableLocation(QStandardPaths::DownloadLocation); + if (downloadFile.isEmpty()) { + _setupState(upgradeStateDownloadFailed); + _ui->statusLabel->setText(tr("Unabled to find writable download location. Tried downloads and temp directory.")); + return; + } + } + Q_ASSERT(!downloadFile.isEmpty()); + downloadFile += "/" + firmwareFilename; + + QUrl firmwareUrl; + if (_firmwareFilename.startsWith("http:")) { + firmwareUrl.setUrl(_firmwareFilename); + } else { + firmwareUrl = QUrl::fromLocalFile(_firmwareFilename); + } + Q_ASSERT(firmwareUrl.isValid()); + + QNetworkRequest networkRequest(firmwareUrl); + + // Store download file location in user attribute so we can retrieve when the download finishes + networkRequest.setAttribute(QNetworkRequest::User, downloadFile); + + _downloadManager = new QNetworkAccessManager(this); + Q_CHECK_PTR(_downloadManager); + _downloadNetworkReply = _downloadManager->get(networkRequest); + Q_ASSERT(_downloadNetworkReply); + connect(_downloadNetworkReply, &QNetworkReply::downloadProgress, this, &PX4FirmwareUpgrade::_downloadProgress); + connect(_downloadNetworkReply, &QNetworkReply::finished, this, &PX4FirmwareUpgrade::_downloadFinished); + // FIXME + //connect(_downloadNetworkReply, &QNetworkReply::error, this, &PX4FirmwareUpgrade::_downloadError); + connect(_downloadNetworkReply, SIGNAL(error(QNetworkReply::NetworkError)), this, SLOT(_downloadError(QNetworkReply::NetworkError))); + + _setupState(upgradeStateFirmwareDownloading); +} + +/// @brief Cancels a download which is in progress. +void PX4FirmwareUpgrade::_cancelDownload(void) +{ + _downloadNetworkReply->abort(); +} + +/// @brief Updates the progress indicator while downloading +void PX4FirmwareUpgrade::_downloadProgress(qint64 curr, qint64 total) +{ + // Take care of cases where 0 / 0 is emitted as error return value + if (total > 0) { + _ui->progressBar->setValue((curr*100) / total); + } +} + +/// @brief Called when the firmware download completes. +void PX4FirmwareUpgrade::_downloadFinished(void) +{ + QNetworkReply* reply = qobject_cast(QObject::sender()); + Q_ASSERT(reply); + + Q_ASSERT(_downloadNetworkReply == reply); + + _downloadManager->deleteLater(); + _downloadManager = NULL; + + // When an error occurs or the user cancels the download, we still end up here. So bail out in + // those cases. + if (reply->error() != QNetworkReply::NoError) { + return; + } + + // Download file location is in user attribute + QString downloadFilename = reply->request().attribute(QNetworkRequest::User).toString(); + Q_ASSERT(!downloadFilename.isEmpty()); + + // Store downloaded file in download location + QFile file(downloadFilename); + if (!file.open(QIODevice::WriteOnly)) { + _ui->statusLabel->setText(tr("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString())); + _setupState(upgradeStateDownloadFailed); + return; + } + + file.write(reply->readAll()); + file.close(); + + + if (downloadFilename.endsWith(".px4")) { + // We need to collect information from the .px4 file as well as pull the binary image out to a seperate file. + + QFile px4File(downloadFilename); + if (!px4File.open(QIODevice::ReadOnly | QIODevice::Text)) { + _ui->statusLabel->setText(tr("Unable to open firmware file %1, error: %2").arg(downloadFilename).arg(px4File.errorString())); + _setupState(upgradeStateDownloadFailed); + return; + } + + QByteArray bytes = px4File.readAll(); + px4File.close(); + QJsonDocument doc = QJsonDocument::fromJson(bytes); + + if (doc.isNull()) { + _ui->statusLabel->setText(tr("supplied file is not a valid JSON document")); + _setupState(upgradeStateDownloadFailed); + return; + } + + QJsonObject px4Json = doc.object(); + + // Make sure the keys we need are available + static const char* rgJsonKeys[] = { "board_id", "image_size", "description", "git_identity" }; + for (size_t i=0; istatusLabel->setText(tr("Incorrectly formatted firmware file. No %1 key.").arg(rgJsonKeys[i])); + _setupState(upgradeStateDownloadFailed); + return; + } + } + + uint32_t firmwareBoardID = (uint32_t)px4Json.value(QString("board_id")).toInt(); + if (firmwareBoardID != _boardID) { + _ui->statusLabel->setText(tr("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardID).arg(_boardID)); + _setupState(upgradeStateDownloadFailed); + return; + } + + _imageSize = px4Json.value(QString("image_size")).toInt(); + if (_imageSize == 0) { + _ui->statusLabel->setText(tr("Image size of 0 in .px4 file %1").arg(downloadFilename)); + _setupState(upgradeStateDownloadFailed); + return; + } + qDebug() << "Image size from px4:" << _imageSize; + + // Convert image from base-64 and decompress + + // XXX Qt's JSON string handling is terribly broken, strings + // with some length (18K / 25K) are just weirdly cut. + // The code below works around this by manually 'parsing' + // for the image string. Since its compressed / checksummed + // this should be fine. + + QStringList list = QString(bytes).split("\"image\": \""); + list = list.last().split("\""); + + // Convert String to QByteArray and unzip it + QByteArray raw; + + // Store image size + raw.append((unsigned char)((_imageSize >> 24) & 0xFF)); + raw.append((unsigned char)((_imageSize >> 16) & 0xFF)); + raw.append((unsigned char)((_imageSize >> 8) & 0xFF)); + raw.append((unsigned char)((_imageSize >> 0) & 0xFF)); + + QByteArray raw64 = list.first().toUtf8(); + + raw.append(QByteArray::fromBase64(raw64)); + QByteArray uncompressed = qUncompress(raw); + + QByteArray b = uncompressed; + + if (b.count() == 0) { + _ui->statusLabel->setText(tr("Firmware file has 0 length image")); + _setupState(upgradeStateDownloadFailed); + return; + } + if (b.count() != (int)_imageSize) { + _ui->statusLabel->setText(tr("Image size for decompressed image does not match stored image size: Expected(%1) Actual(%2)").arg(_imageSize).arg(b.count())); + _setupState(upgradeStateDownloadFailed); + return; + } + + // Pad image to 4-byte boundary + while ((b.count() % 4) != 0) { + b.append(static_cast(static_cast(0xFF))); + } + + // Store decompressed image file in same location as original download file + QDir downloadDir = QFileInfo(downloadFilename).dir(); + QString decompressFilename = downloadDir.filePath("PX4FlashUpgrade.bin"); + + QFile decompressFile(decompressFilename); + if (!decompressFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) { + _ui->statusLabel->setText(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename).arg(decompressFile.errorString())); + _setupState(upgradeStateDownloadFailed); + return; + } + + qint64 bytesWritten = decompressFile.write(b); + if (bytesWritten != b.count()) { + _ui->statusLabel->setText(tr("Write failed for decompressed image file, error: %1").arg(decompressFile.errorString())); + _setupState(upgradeStateDownloadFailed); + return; + } + decompressFile.close(); + + _firmwareFilename = decompressFilename; + } else if (downloadFilename.endsWith(".bin")) { + uint32_t firmwareBoardID = 0; + + // Take some educated guesses on board id based on firmware build system file name conventions + + if (downloadFilename.toLower().contains("px4fmu-v1")) { + firmwareBoardID = _boardIDPX4FMUV2; + } else if (downloadFilename.toLower().contains("px4flow")) { + firmwareBoardID = _boardIDPX4Flow; + } else if (downloadFilename.toLower().contains("px4fmu-v1")) { + firmwareBoardID = _boardIDPX4FMUV1; + } + + if (firmwareBoardID != 0 && firmwareBoardID != _boardID) { + _ui->statusLabel->setText(tr("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardID).arg(_boardID)); + _setupState(upgradeStateDownloadFailed); + return; + } + + _firmwareFilename = downloadFilename; + + QFile binFile(_firmwareFilename); + if (!binFile.open(QIODevice::ReadOnly)) { + _ui->statusLabel->setText(tr("Unabled to open firmware file %1, %2").arg(_firmwareFilename).arg(binFile.errorString())); + _setupState(upgradeStateDownloadFailed); + } + _imageSize = (uint32_t)binFile.size(); + binFile.close(); + } else { + // Standard firmware builds (stable/continuous/...) are always .bin or .px4. Select file dialog for custom + // firmware filters to .bin and .px4. So we should never get a file that ends in anything else. + Q_ASSERT(false); + } + + if (_imageSize > _boardFlashSize) { + _ui->statusLabel->setText(tr("Image size of %1 is too large for board flash size %2").arg(_imageSize).arg(_boardFlashSize)); + _setupState(upgradeStateDownloadFailed); + return; + } + + _erase(); +} + +/// @brief Called when an error occurs during download +void PX4FirmwareUpgrade::_downloadError(QNetworkReply::NetworkError code) +{ + if (code == QNetworkReply::OperationCanceledError) { + _ui->statusLabel->setText(tr("Download cancelled")); + } else { + _ui->statusLabel->setText(tr("Error during download. Error: %1").arg(code)); + } + + _setupState(upgradeStateDownloadFailed); +} + +/// @brief Erase the board +void PX4FirmwareUpgrade::_erase(void) +{ + // We set up our own progress bar for erase since the erase command does not provide one + _eraseTickCount = 0; + _eraseTimer.start(_eraseTickMsec); + _setupState(upgradeStateErasing); + + // Erase command + _threadController->erase(); +} + +/// @brief Signals completion of one of the specified bootloader commands. Moves the state machine to the +/// appropriate next step. +void PX4FirmwareUpgrade::_complete(const int command) +{ + if (command == PX4FirmwareUpgradeThreadWorker::commandProgram) { + _setupState(upgradeStateVerifying); + _threadController->verify(_firmwareFilename); + } else if (command == PX4FirmwareUpgradeThreadWorker::commandVerify) { + _setupState(upgradeStateBoardUpgraded); + } else if (command == PX4FirmwareUpgradeThreadWorker::commandErase) { + _eraseTimer.stop(); + _setupState(upgradeStateFlashing); + _threadController->program(_firmwareFilename); + } else if (command == PX4FirmwareUpgradeThreadWorker::commandCancel) { + if (_upgradeState == upgradeStateBoardSearch) { + _setupState(upgradeStateBoardNotFound); + } else if (_upgradeState == upgradeStateBootloaderSearch) { + _setupState(upgradeStateBootloaderNotFound); + } else { + Q_ASSERT(false); + } + } else { + Q_ASSERT(false); + } +} + +/// @brief Signals that an error has occured with the specified bootloader commands. Moves the state machine +/// to the appropriate error state. +void PX4FirmwareUpgrade::_error(const int command, const QString errorString) +{ + _ui->statusLabel->setText(tr("Error: %1").arg(errorString)); + + if (command == PX4FirmwareUpgradeThreadWorker::commandProgram) { + _setupState(upgradeStateFlashError); + } else if (command == PX4FirmwareUpgradeThreadWorker::commandErase) { + _setupState(upgradeStateEraseError); + } else if (command == PX4FirmwareUpgradeThreadWorker::commandBootloader) { + _setupState(upgradeStateBootloaderError); + } else if (command == PX4FirmwareUpgradeThreadWorker::commandVerify) { + _setupState(upgradeStateVerifyError); + } else { + Q_ASSERT(false); + } +} + +/// @brief Updates the progress bar from long running bootloader commands +void PX4FirmwareUpgrade::_updateProgress(int curr, int total) +{ + _ui->progressBar->setValue((curr*100) / total); +} + +/// @brief Resets the state machine back to the beginning +void PX4FirmwareUpgrade::_restart(void) +{ + _setupState(upgradeStateBegin); +} + +/// @brief Moves the progress bar ahead on tick while erasing the board +void PX4FirmwareUpgrade::_eraseProgressTick(void) +{ + _eraseTickCount++; + _ui->progressBar->setValue((_eraseTickCount*_eraseTickMsec*100) / _eraseTotalMsec); +} \ No newline at end of file diff --git a/src/ui/px4_configuration/PX4FirmwareUpgrade.h b/src/ui/px4_configuration/PX4FirmwareUpgrade.h new file mode 100644 index 0000000000000000000000000000000000000000..ad3e6afe27091a6ceac7624ad79ab341d1fbf0a7 --- /dev/null +++ b/src/ui/px4_configuration/PX4FirmwareUpgrade.h @@ -0,0 +1,159 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief PX4 Firmware Upgrade UI +/// @author Don Gagne + +#ifndef PX4FirmwareUpgrade_H +#define PX4FirmwareUpgrade_H + +#include +#include +#include +#include +#include +#include + +#include + +#include "PX4FirmwareUpgradeThread.h" + +#include "ui_PX4FirmwareUpgrade.h" + +namespace Ui { + class PX4RCCalibration; +} + +class PX4FirmwareUpgrade : public QWidget +{ + Q_OBJECT + +public: + explicit PX4FirmwareUpgrade(QWidget *parent = 0); + ~PX4FirmwareUpgrade(); + +private slots: + void _tryAgainButton(void); + void _cancelButton(void); + void _nextButton(void); + void _firmwareSelected(int index); + void _downloadProgress(qint64 curr, qint64 total); + void _downloadFinished(void); + void _downloadError(QNetworkReply::NetworkError code); + void _foundBoard(const QString portname, QString portDescription); + void _foundBootloader(int bootloaderVersion, int boardID, int flashSize); + void _error(const int command, const QString errorString); + void _bootloaderSyncFailed(void); + void _findTimeout(void); + void _complete(const int command); + void _updateProgress(int curr, int total); + void _restart(void); + void _eraseProgressTick(void); + +private: + /// @brief The various states that the upgrade process progresses through. + enum upgradeStates { + upgradeStateBegin, + upgradeStateBoardSearch, + upgradeStateBoardNotFound, + upgradeStateBootloaderSearch, + upgradeStateBootloaderNotFound, + upgradeStateBootloaderError, + upgradeStateFirmwareSelect, + upgradeStateFirmwareDownloading, + upgradeStateDownloadFailed, + upgradeStateErasing, + upgradeStateEraseError, + upgradeStateFlashing, + upgradeStateFlashError, + upgradeStateVerifying, + upgradeStateVerifyError, + upgradeStateBoardUpgraded, + upgradeStateMax + }; + + void _setupState(enum upgradeStates state); + void _updateIndicatorUI(void); + + void _findBoard(void); + void _findBootloader(void); + void _cancel(void); + void _cancelFind(void); + void _getFirmwareFile(void); + + void _setBoardIcon(int boardID); + void _setFirmwareCombo(int boardID); + + void _downloadFirmware(void); + void _cancelDownload(void); + + void _erase(void); + + typedef void (PX4FirmwareUpgrade::*stateFunc)(void); + struct stateMachineEntry { + enum upgradeStates state; ///< State machine state, used to verify correctness of entry + stateFunc next; ///< Method to call when Next is clicked, NULL for Next not available + stateFunc cancel; ///< Method to call when Cancel is clicked, NULL for Cancel not available + stateFunc tryAgain; ///< Method to call when Try Again is clicked, NULL for Try Again not available + const char* msg; ///< Text message to display to user for this state + }; + + const struct stateMachineEntry* _getStateMachineEntry(enum upgradeStates state); + + enum upgradeStates _upgradeState; ///< Current state of the upgrade state machines + + QString _portName; + QString _portDescription; + uint32_t _bootloaderVersion; + + static const int _boardIDPX4FMUV1 = 5; ///< Board ID for PX4 V1 board + static const int _boardIDPX4FMUV2 = 9; ///< Board ID for PX4 V2 board + static const int _boardIDPX4Flow = 6; ///< Board ID for PX4 Flow board + + uint32_t _boardID; ///< Board ID + uint32_t _boardFlashSize; ///< Flash size in bytes of board + uint32_t _imageSize; ///< Image size of firmware being flashed + + QPixmap _boardIcon; ///< Icon used to display image of board + + QString _firmwareFilename; ///< Image which we are going to flash to the board + + QNetworkAccessManager* _downloadManager; ///< Used for firmware file downloading across the internet + QNetworkReply* _downloadNetworkReply; ///< Used for firmware file downloading across the internet + + /// @brief Thread controller which is used to run bootloader commands on seperate thread + PX4FirmwareUpgradeThreadController* _threadController; + + static const int _eraseTickMsec = 500; ///< Progress bar update tick time for erase + static const int _eraseTotalMsec = 15000; ///< Estimated amount of time erase takes + int _eraseTickCount; ///< Number of ticks for erase progress update + QTimer _eraseTimer; ///< Timer used to update progress bar for erase + + static const int _findBoardTimeoutMsec = 30000; ///< Amount of time for user to plug in USB + static const int _findBootloaderTimeoutMsec = 5000; ///< Amount time to look for bootloader + + Ui::PX4FirmwareUpgrade* _ui; +}; + +#endif // PX4FirmwareUpgrade_H diff --git a/src/ui/px4_configuration/PX4FirmwareUpgrade.ui b/src/ui/px4_configuration/PX4FirmwareUpgrade.ui new file mode 100644 index 0000000000000000000000000000000000000000..ad460b87ddbe126859f781c5d7cc61d338f7c9e6 --- /dev/null +++ b/src/ui/px4_configuration/PX4FirmwareUpgrade.ui @@ -0,0 +1,245 @@ + + + PX4FirmwareUpgrade + + + + 0 + 0 + 1562 + 1286 + + + + Form + + + + + 0 + 0 + 726 + 525 + + + + + + + + + Board found + + + + + + + Port + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Description + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Bootloader found + + + + + + + Bootloader Version + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Board ID + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + + 200 + 100 + + + + Icon + + + + + + + Select Firmware + + + + + + + + + + Firmware downloaded + + + + + + + Board upgraded + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + 0 + 0 + + + + + 400 + 180 + + + + Status log + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + + 0 + 0 + + + + + 400 + 16 + + + + TextLabel + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + + + Try Again + + + + + + + Skip + + + + + + + Cancel + + + + + + + Next + + + + + + + + + 24 + + + + + + + Qt::Vertical + + + + 20 + 60 + + + + + + + + + + + + diff --git a/src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc new file mode 100644 index 0000000000000000000000000000000000000000..496fec388c11c4b5959d14bd9f356ce8ab5f6461 --- /dev/null +++ b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc @@ -0,0 +1,306 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief PX4 Firmware Upgrade operations which occur on a seperate thread. +/// @author Don Gagne + +#include "PX4FirmwareUpgradeThread.h" +#include "PX4Bootloader.h" + +#include +#include +#include + +PX4FirmwareUpgradeThreadWorker::PX4FirmwareUpgradeThreadWorker(QObject* parent) : + QObject(parent), + _bootloader(NULL), + _bootloaderPort(NULL), + _timerTimeout(NULL), + _timerRetry(NULL) +{ + +} + +PX4FirmwareUpgradeThreadWorker::~PX4FirmwareUpgradeThreadWorker() +{ + if (_bootloaderPort) { + // deleteLater so delete happens on correct thread + _bootloaderPort->deleteLater(); + } +} + +/// @brief Initializes the PX4FirmwareUpgradeThreadWorker with the various child objects which must be created +/// on the worker thread. +void PX4FirmwareUpgradeThreadWorker::init(void) +{ + // We create the timers here so that they are on the right thread + + Q_ASSERT(_timerTimeout == NULL); + _timerTimeout = new QTimer(this); + Q_CHECK_PTR(_timerTimeout); + connect(_timerTimeout, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::timeout); + _timerTimeout->setSingleShot(true); + + Q_ASSERT(_timerRetry == NULL); + _timerRetry = new QTimer(this); + Q_CHECK_PTR(_timerRetry); + _timerRetry->setSingleShot(true); + _timerRetry->setInterval(_retryTimeout); + + Q_ASSERT(_bootloader == NULL); + _bootloader = new PX4Bootloader(this); + connect(_bootloader, &PX4Bootloader::updateProgramProgress, this, &PX4FirmwareUpgradeThreadWorker::_updateProgramProgress); +} + +void PX4FirmwareUpgradeThreadWorker::findBoard(int msecTimeout) +{ + connect(_timerRetry, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::_findBoardOnce); + _timerTimeout->start(msecTimeout); + _elapsed.start(); + _findBoardOnce(); +} + +void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void) +{ + qDebug() << "_findBoardOnce"; + + QString portName; + QString portDescription; + + foreach (QSerialPortInfo info, QSerialPortInfo::availablePorts()) { + if (!info.portName().isEmpty() && (info.description().contains("PX4") || info.vendorIdentifier() == 9900 /* 3DR */)) { + + qDebug() << "Found Board:"; + qDebug() << "\tport name:" << info.portName(); + qDebug() << "\tdescription:" << info.description(); + qDebug() << "\tsystem location:" << info.systemLocation(); + qDebug() << "\tvendor ID:" << info.vendorIdentifier(); + qDebug() << "\tproduct ID:" << info.productIdentifier(); + + portName = info.portName(); + portDescription = info.description(); + +#ifdef Q_OS_WIN + // Stupid windows fixes + portName.prepend("\\\\.\\"); +#endif + + _closeFind(); + emit foundBoard(portName, portDescription); + return; + } + } + + emit updateProgress(_elapsed.elapsed(), _timerTimeout->interval()); + _timerRetry->start(); +} + +void PX4FirmwareUpgradeThreadWorker::findBootloader(const QString portName, int msecTimeout) +{ + connect(_timerRetry, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::_findBootloaderOnce); + _portName = portName; + _timerTimeout->start(msecTimeout); + _elapsed.start(); + _findBootloaderOnce(); +} + +void PX4FirmwareUpgradeThreadWorker::_findBootloaderOnce(void) +{ + qDebug() << "_findBootloaderOnce"; + + uint32_t bootloaderVersion, boardID, flashSize; + + _bootloaderPort = new QSerialPort; + Q_CHECK_PTR(_bootloaderPort); + + if (_bootloader->open(_bootloaderPort, _portName)) { + if (_bootloader->sync(_bootloaderPort)) { + if (_bootloader->getBoardInfo(_bootloaderPort, bootloaderVersion, boardID, flashSize)) { + _closeFind(); + qDebug() << "Found bootloader"; + emit foundBootloader(bootloaderVersion, boardID, flashSize); + return; + } else { + _closeFind(); + _bootloaderPort->close(); + _bootloaderPort->deleteLater(); + _bootloaderPort = NULL; + qDebug() << "Bootloader error:" << _bootloader->errorString(); + emit error(commandBootloader, _bootloader->errorString()); + return; + } + } else { + _closeFind(); + _bootloaderPort->close(); + _bootloaderPort->deleteLater(); + _bootloaderPort = NULL; + qDebug() << "Bootloader sync failed"; + emit bootloaderSyncFailed(); + return; + } + } + + emit updateProgress(_elapsed.elapsed(), _timerTimeout->interval()); + _timerRetry->start(); +} + +void PX4FirmwareUpgradeThreadWorker::_closeFind(void) +{ + emit updateProgress(100, 100); + disconnect(_timerRetry, SIGNAL(timeout()), 0, 0); + _timerRetry->stop(); + _timerTimeout->stop(); +} + +void PX4FirmwareUpgradeThreadWorker::cancelFind(void) +{ + _closeFind(); + emit complete(commandCancel); +} + +void PX4FirmwareUpgradeThreadWorker::timeout(void) +{ + qDebug() << "Find timeout"; + _closeFind(); + emit findTimeout(); +} + +void PX4FirmwareUpgradeThreadWorker::sendBootloaderReboot(void) +{ + _bootloader->sendBootloaderReboot(_bootloaderPort); + _bootloaderPort->deleteLater(); + _bootloaderPort = NULL; +} + +void PX4FirmwareUpgradeThreadWorker::program(const QString firmwareFilename) +{ + qDebug() << "Program"; + if (!_bootloader->program(_bootloaderPort, firmwareFilename)) { + _bootloaderPort->deleteLater(); + _bootloaderPort = NULL; + qDebug() << "Program failed:" << _bootloader->errorString(); + emit error(commandProgram, _bootloader->errorString()); + } else { + qDebug() << "Program complete"; + emit complete(commandProgram); + } +} + +void PX4FirmwareUpgradeThreadWorker::verify(const QString firmwareFilename) +{ + qDebug() << "Verify"; + if (!_bootloader->verify(_bootloaderPort, firmwareFilename)) { + qDebug() << "Verify failed:" << _bootloader->errorString(); + emit error(commandVerify, _bootloader->errorString()); + } else { + qDebug() << "Verify complete"; + emit complete(commandVerify); + } + _bootloaderPort->deleteLater(); + _bootloaderPort = NULL; +} + +void PX4FirmwareUpgradeThreadWorker::erase(void) +{ + qDebug() << "Erase"; + if (!_bootloader->erase(_bootloaderPort)) { + _bootloaderPort->deleteLater(); + _bootloaderPort = NULL; + qDebug() << "Erase failed:" << _bootloader->errorString(); + emit error(commandErase, _bootloader->errorString()); + } else { + qDebug() << "Erase complete"; + emit complete(commandErase); + } +} + +PX4FirmwareUpgradeThreadController::PX4FirmwareUpgradeThreadController(QObject* parent) : + QObject(parent) +{ + _worker = new PX4FirmwareUpgradeThreadWorker(); + Q_CHECK_PTR(_worker); + + _workerThread = new QThread(this); + Q_CHECK_PTR(_workerThread); + _worker->moveToThread(_workerThread); + + connect(_worker, &PX4FirmwareUpgradeThreadWorker::foundBoard, this, &PX4FirmwareUpgradeThreadController::_foundBoard); + connect(_worker, &PX4FirmwareUpgradeThreadWorker::foundBootloader, this, &PX4FirmwareUpgradeThreadController::_foundBootloader); + connect(_worker, &PX4FirmwareUpgradeThreadWorker::bootloaderSyncFailed, this, &PX4FirmwareUpgradeThreadController::_bootloaderSyncFailed); + connect(_worker, &PX4FirmwareUpgradeThreadWorker::error, this, &PX4FirmwareUpgradeThreadController::_error); + connect(_worker, &PX4FirmwareUpgradeThreadWorker::complete, this, &PX4FirmwareUpgradeThreadController::_complete); + connect(_worker, &PX4FirmwareUpgradeThreadWorker::findTimeout, this, &PX4FirmwareUpgradeThreadController::_findTimeout); + connect(_worker, &PX4FirmwareUpgradeThreadWorker::updateProgress, this, &PX4FirmwareUpgradeThreadController::_updateProgress); + + connect(this, &PX4FirmwareUpgradeThreadController::_initThreadWorker, _worker, &PX4FirmwareUpgradeThreadWorker::init); + connect(this, &PX4FirmwareUpgradeThreadController::_findBoardOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::findBoard); + connect(this, &PX4FirmwareUpgradeThreadController::_findBootloaderOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::findBootloader); + connect(this, &PX4FirmwareUpgradeThreadController::_sendBootloaderRebootOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::sendBootloaderReboot); + connect(this, &PX4FirmwareUpgradeThreadController::_programOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::program); + connect(this, &PX4FirmwareUpgradeThreadController::_verifyOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::verify); + connect(this, &PX4FirmwareUpgradeThreadController::_eraseOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::erase); + connect(this, &PX4FirmwareUpgradeThreadController::_cancelFindOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::cancelFind); + + _workerThread->start(); + + emit _initThreadWorker(); +} + +PX4FirmwareUpgradeThreadController::~PX4FirmwareUpgradeThreadController() +{ + _workerThread->quit(); + _workerThread->wait(); +} + +void PX4FirmwareUpgradeThreadController::findBoard(int msecTimeout) +{ + qDebug() << "PX4FirmwareUpgradeThreadController::findBoard"; + emit _findBoardOnThread(msecTimeout); +} + +void PX4FirmwareUpgradeThreadController::findBootloader(const QString& portName, int msecTimeout) +{ + qDebug() << "PX4FirmwareUpgradeThreadController::findBootloader"; + emit _findBootloaderOnThread(portName, msecTimeout); +} + +void PX4FirmwareUpgradeThreadController::_foundBoard(const QString portName, QString portDescription) +{ + emit foundBoard(portName, portDescription); +} + +void PX4FirmwareUpgradeThreadController::_foundBootloader(int bootloaderVersion, int boardID, int flashSize) +{ + emit foundBootloader(bootloaderVersion, boardID, flashSize); +} + +void PX4FirmwareUpgradeThreadController::_bootloaderSyncFailed(void) +{ + emit bootloaderSyncFailed(); +} + +void PX4FirmwareUpgradeThreadController::_findTimeout(void) +{ + emit findTimeout(); +} diff --git a/src/ui/px4_configuration/PX4FirmwareUpgradeThread.h b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.h new file mode 100644 index 0000000000000000000000000000000000000000..f51362b06ad12354f35790f541add5cb45bd8bbc --- /dev/null +++ b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.h @@ -0,0 +1,180 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief PX4 Firmware Upgrade operations which occur on a seperate thread. +/// @author Don Gagne + +#ifndef PX4FirmwareUpgradeThread_H +#define PX4FirmwareUpgradeThread_H + +#include +#include +#include +#include +#include + +#include + +#include "PX4Bootloader.h" + +/// @brief Used to run bootloader commands on a seperate thread. These routines are mainly meant to to be called +/// internally by the PX4FirmwareUpgradeThreadController. Clients should call the various public methods +/// exposed by PX4FirmwareUpgradeThreadController. +class PX4FirmwareUpgradeThreadWorker : public QObject +{ + Q_OBJECT + +public: + PX4FirmwareUpgradeThreadWorker(QObject* parent = NULL); + ~PX4FirmwareUpgradeThreadWorker(); + + enum { + commandBootloader, + commandProgram, + commandVerify, + commandErase, + commandCancel + }; + +public slots: + void init(void); + void findBoard(int msecTimeout); + void findBootloader(const QString portName, int msecTimeout); + void timeout(void); + void cancelFind(void); + void sendBootloaderReboot(void); + void program(const QString firmwareFilename); + void verify(const QString firmwareFilename); + void erase(void); + +signals: + void foundBoard(const QString portname, QString portDescription); + void foundBootloader(int bootloaderVersion, int boardID, int flashSize); + void bootloaderSyncFailed(void); + void error(const int command, const QString errorString); + void complete(const int command); + void findTimeout(void); + void updateProgress(int curr, int total); + +private slots: + void _findBoardOnce(void); + void _findBootloaderOnce(void); + void _updateProgramProgress(int curr, int total) { emit updateProgress(curr, total); } + void _closeFind(void); + +private: + PX4Bootloader* _bootloader; + QSerialPort* _bootloaderPort; + QTimer* _timerTimeout; + QTimer* _timerRetry; + QTime _elapsed; + QString _portName; + static const int _retryTimeout = 1000; +}; + +/// @brief Provides methods to interact with the bootloader. The commands themselves are signalled +/// across to PX4FirmwareUpgradeThreadWorker so that they run on the seperate thread. +class PX4FirmwareUpgradeThreadController : public QObject +{ + Q_OBJECT + +public: + PX4FirmwareUpgradeThreadController(QObject* parent = NULL); + ~PX4FirmwareUpgradeThreadController(void); + + /// @brief Begins the process of searching for a PX4 board connected to any serial port. + /// @param msecTimeout Numbers of msecs to continue looking for a board to become available. + void findBoard(int msecTimeout); + + /// @brief Begins the process of attempting to communicate with the bootloader on the specified port. + /// @param portName Name of port to attempt a bootloader connection on. + /// @param msecTimeout Number of msecs to continue to wait for a bootloader to appear on the port. + void findBootloader(const QString& portName, int msecTimeout); + + /// @brief Cancel an in progress findBoard or FindBootloader + void cancelFind(void) { emit _cancelFindOnThread(); } + + /// @brief Sends a reboot command to the bootloader + void sendBootloaderReboot(void) { emit _sendBootloaderRebootOnThread(); } + + /// @brief Flash the specified firmware onto the board + void program(const QString firmwareFilename) { emit _programOnThread(firmwareFilename); } + + /// @brief Verify the board flash with respect to the specified firmware image + void verify(const QString firmwareFilename) { emit _verifyOnThread(firmwareFilename); } + + /// @brief Send and erase command to the bootloader + void erase(void) { emit _eraseOnThread(); } + +signals: + /// @brief Emitted by the findBoard process when it finds the board. + /// @param portName Port that board is on + /// @param portDescription User friendly port description + void foundBoard(const QString portname, QString portDescription); + + /// @brief Emitted by the findBootloader process when has a connection to the bootloader + void foundBootloader(int bootloaderVersion, int boardID, int flashSize); + + /// @brief Emitted by the bootloader commands when an error occurs. + /// @param errorCommand Command which caused the error, using PX4FirmwareUpgradeThreadWorker command* enum values + void error(const int errorCommand, const QString errorString); + + /// @brief Signalled when the findBootloader process connects to the port, but cannot sync to the + /// bootloader. + void bootloaderSyncFailed(void); + + /// @brief Signalled when the findBoard or findBootloader process times out before success + void findTimeout(void); + + /// @brief Signalled by the bootloader commands other than find* that they have complete successfully. + /// @param command Command which completed, using PX4FirmwareUpgradeThreadWorker command* enum values + void complete(const int command); + + /// @brief Signalled to update progress for long running bootloader commands + void updateProgress(int curr, int total); + + void _initThreadWorker(void); + void _findBoardOnThread(int msecTimeout); + void _findBootloaderOnThread(const QString& portName, int msecTimeout); + void _sendBootloaderRebootOnThread(void); + void _programOnThread(const QString firmwareFilename); + void _verifyOnThread(const QString firmwareFilename); + void _eraseOnThread(void); + void _cancelFindOnThread(void); + +private slots: + void _foundBoard(const QString portname, QString portDescription); + void _foundBootloader(int bootloaderVersion, int boardID, int flashSize); + void _bootloaderSyncFailed(void); + void _error(const int errorCommand, const QString errorString) { emit error(errorCommand, errorString); } + void _complete(const int command) { emit complete(command); } + void _findTimeout(void); + void _updateProgress(int curr, int total) { emit updateProgress(curr, total); } + +private: + PX4FirmwareUpgradeThreadWorker* _worker; + QThread* _workerThread; ///< Thread which PX4FirmwareUpgradeThreadWorker runs on +}; + +#endif diff --git a/src/ui/px4_configuration/QGCPX4AirframeConfig.cc b/src/ui/px4_configuration/QGCPX4AirframeConfig.cc index f62543ce879e05ad0e45d3c949d26542a5a568e2..4eaa95fdb564b607a6d94110fc0cebf134f3cc44 100644 --- a/src/ui/px4_configuration/QGCPX4AirframeConfig.cc +++ b/src/ui/px4_configuration/QGCPX4AirframeConfig.cc @@ -56,23 +56,24 @@ QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) : ui->quadXComboBox->addItem(tr("DJI F330 8\" Quad"), 4010); ui->quadXComboBox->addItem(tr("DJI F450 10\" Quad"), 4011); - ui->quadXComboBox->addItem(tr("Turnigy Talon v2 X550 Quad"), 4012); + ui->quadXComboBox->addItem(tr("X frame Quad UAVCAN"), 4012); ui->quadXComboBox->addItem(tr("AR.Drone Frame Quad"), 4008); - ui->quadXComboBox->addItem(tr("DJI F330 with MK BLCTRL"), 4017); - ui->quadXComboBox->addItem(tr("Mikrokopter X frame"), 4019); +// ui->quadXComboBox->addItem(tr("DJI F330 with MK BLCTRL"), 4017); +// ui->quadXComboBox->addItem(tr("Mikrokopter X frame"), 4019); connect(ui->quadXPushButton, SIGNAL(clicked()), this, SLOT(quadXSelected())); connect(ui->quadXComboBox, SIGNAL(activated(int)), this, SLOT(quadXSelected(int))); ui->quadXPushButton->setEnabled(ui->quadXComboBox->count() > 0); ui->quadPlusComboBox->addItem(tr("Generic 10\" Quad +"), 5001); - ui->quadXComboBox->addItem(tr("Mikrokopter + frame"), 5020); +// ui->quadXComboBox->addItem(tr("Mikrokopter + frame"), 5020); connect(ui->quadPlusPushButton, SIGNAL(clicked()), this, SLOT(quadPlusSelected())); connect(ui->quadPlusComboBox, SIGNAL(activated(int)), this, SLOT(quadPlusSelected(int))); ui->quadPlusPushButton->setEnabled(ui->quadPlusComboBox->count() > 0); - ui->hexaXComboBox->addItem(tr("Standard 10\" Hexa"), 6001); + ui->hexaXComboBox->addItem(tr("Standard 10\" Hexa X"), 6001); + ui->hexaXComboBox->addItem(tr("Coaxial 10\" Hexa X"), 11001); connect(ui->hexaXPushButton, SIGNAL(clicked()), this, SLOT(hexaXSelected())); connect(ui->hexaXComboBox, SIGNAL(activated(int)), this, SLOT(hexaXSelected(int))); @@ -85,6 +86,7 @@ QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) : ui->hexaPlusPushButton->setEnabled(ui->hexaPlusComboBox->count() > 0); ui->octoXComboBox->addItem(tr("Standard 10\" Octo"), 8001); + ui->octoXComboBox->addItem(tr("Coaxial 10\" Octo"), 12001); connect(ui->octoXPushButton, SIGNAL(clicked()), this, SLOT(octoXSelected())); connect(ui->octoXComboBox, SIGNAL(activated(int)), this, SLOT(octoXSelected(int))); diff --git a/src/ui/px4_configuration/QGCPX4SensorCalibration.cc b/src/ui/px4_configuration/QGCPX4SensorCalibration.cc index a0b075944026dbc6e74d6efb4cda13d82a7bb957..54deff7f201bda1ce1a4b2db3c35044d91d98e9d 100644 --- a/src/ui/px4_configuration/QGCPX4SensorCalibration.cc +++ b/src/ui/px4_configuration/QGCPX4SensorCalibration.cc @@ -19,6 +19,10 @@ QGCPX4SensorCalibration::QGCPX4SensorCalibration(QWidget *parent) : connect(ui->accelButton, SIGNAL(clicked()), this, SLOT(accelButtonClicked())); connect(ui->diffPressureButton, SIGNAL(clicked()), this, SLOT(diffPressureButtonClicked())); + connect(ui->logCheckBox, SIGNAL(clicked(bool)), ui->textView, SLOT(setVisible(bool))); + ui->logCheckBox->setChecked(false); + ui->textView->setVisible(false); + ui->gyroButton->setEnabled(false); ui->magButton->setEnabled(false); ui->accelButton->setEnabled(false); diff --git a/src/ui/px4_configuration/QGCPX4SensorCalibration.ui b/src/ui/px4_configuration/QGCPX4SensorCalibration.ui index b1fd81425e547ba98420fb32634d757b78ffc095..a99e1dbaeb8e39d74edff2af36c10943a3db1273 100644 --- a/src/ui/px4_configuration/QGCPX4SensorCalibration.ui +++ b/src/ui/px4_configuration/QGCPX4SensorCalibration.ui @@ -7,7 +7,7 @@ 0 0 659 - 603 + 636 @@ -36,24 +36,75 @@ QPushButton#gyroButton, QPushButton#accelButton, QPushButton#diffPressureButton border: 2px solid #465158; } - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + Autopilot Orientation + + + + + + + 0 + 250 + + + + + + + + + + + + + + + + + Magnetometer Orientation + + + + + + + 150 + 120 + + + + + + + + + + + + + + - + Qt::Vertical @@ -66,8 +117,29 @@ QPushButton#gyroButton, QPushButton#accelButton, QPushButton#diffPressureButton - - + + + + + + + + + + + 24 + + + + + + + false + + + + + @@ -154,76 +226,45 @@ QPushButton#gyroButton, QPushButton#accelButton, QPushButton#diffPressureButton - - - - 24 + + + + - - - - Autopilot Orientation + + + + Qt::Horizontal - - - - - - 0 - 250 - - - - - - - - - - - - - - - - - + + + 40 + 20 + - + - - + + - + Log - - - - Magnetometer Orientation + + + + Qt::Horizontal - - - - - - 150 - 120 - - - - - - - - - - - - + + + 40 + 20 + + +