From f3286d58ea086f25d55bd39fd47bacb994fc4d4b Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 22 Oct 2014 15:23:06 -0700 Subject: [PATCH] Remove unreachable APM code --- qgroundcontrol.pro | 89 -- src/comm/MAVLinkProtocol.cc | 1 - src/comm/MAVLinkSimulationLink.cc | 22 - src/comm/MAVLinkSimulationMAV.cc | 2 +- src/qgcunittest/FlightModeConfigTest.cc | 306 ----- src/qgcunittest/FlightModeConfigTest.h | 87 -- src/uas/ArduPilotMegaMAV.cc | 132 -- src/uas/ArduPilotMegaMAV.h | 45 - src/uas/QGCMAVLinkUASFactory.cc | 15 - src/uas/QGCMAVLinkUASFactory.h | 1 - src/ui/MainWindow.cc | 106 +- src/ui/MainWindow.h | 1 - src/ui/MainWindow.ui | 3 +- src/ui/apmtoolbar.cpp | 215 ---- src/ui/apmtoolbar.h | 57 - src/ui/configuration/AP2ConfigWidget.cc | 36 - src/ui/configuration/AP2ConfigWidget.h | 23 - .../configuration/AccelCalibrationConfig.cc | 132 -- src/ui/configuration/AccelCalibrationConfig.h | 28 - .../configuration/AccelCalibrationConfig.ui | 62 - src/ui/configuration/AdvParameterList.cc | 55 - src/ui/configuration/AdvParameterList.h | 25 - src/ui/configuration/AdvParameterList.ui | 31 - src/ui/configuration/AdvancedParamConfig.cc | 67 -- src/ui/configuration/AdvancedParamConfig.h | 26 - src/ui/configuration/AdvancedParamConfig.ui | 50 - src/ui/configuration/AirspeedConfig.cc | 86 -- src/ui/configuration/AirspeedConfig.h | 23 - src/ui/configuration/AirspeedConfig.ui | 82 -- src/ui/configuration/AntennaTrackerConfig.cc | 11 - src/ui/configuration/AntennaTrackerConfig.h | 19 - src/ui/configuration/AntennaTrackerConfig.ui | 311 ----- src/ui/configuration/ApmFirmwareConfig.cc | 462 ------- src/ui/configuration/ApmFirmwareConfig.h | 66 - src/ui/configuration/ApmFirmwareConfig.ui | 514 -------- src/ui/configuration/ApmHardwareConfig.cc | 187 --- src/ui/configuration/ApmHardwareConfig.h | 88 -- src/ui/configuration/ApmHardwareConfig.ui | 330 ----- src/ui/configuration/ApmPlaneLevel.cc | 69 -- src/ui/configuration/ApmPlaneLevel.h | 23 - src/ui/configuration/ApmPlaneLevel.ui | 99 -- src/ui/configuration/ApmSoftwareConfig.cc | 368 ------ src/ui/configuration/ApmSoftwareConfig.h | 44 - src/ui/configuration/ApmSoftwareConfig.ui | 210 ---- src/ui/configuration/ArduCopterPidConfig.cc | 210 ---- src/ui/configuration/ArduCopterPidConfig.h | 30 - src/ui/configuration/ArduCopterPidConfig.ui | 1061 ----------------- src/ui/configuration/ArduPlanePidConfig.cc | 102 -- src/ui/configuration/ArduPlanePidConfig.h | 24 - src/ui/configuration/ArduPlanePidConfig.ui | 963 --------------- src/ui/configuration/ArduRoverPidConfig.cc | 83 -- src/ui/configuration/ArduRoverPidConfig.h | 23 - src/ui/configuration/ArduRoverPidConfig.ui | 732 ------------ src/ui/configuration/BasicPidConfig.cc | 11 - src/ui/configuration/BasicPidConfig.h | 19 - src/ui/configuration/BasicPidConfig.ui | 32 - src/ui/configuration/BatteryMonitorConfig.cc | 320 ----- src/ui/configuration/BatteryMonitorConfig.h | 32 - src/ui/configuration/BatteryMonitorConfig.ui | 231 ---- src/ui/configuration/CameraGimbalConfig.cc | 669 ----------- src/ui/configuration/CameraGimbalConfig.h | 32 - src/ui/configuration/CameraGimbalConfig.ui | 965 --------------- src/ui/configuration/CompassConfig.cc | 139 --- src/ui/configuration/CompassConfig.h | 25 - src/ui/configuration/CompassConfig.ui | 196 --- src/ui/configuration/FailSafeConfig.cc | 447 ------- src/ui/configuration/FailSafeConfig.h | 33 - src/ui/configuration/FailSafeConfig.ui | 452 ------- src/ui/configuration/FlightModeConfig.cc | 285 ----- src/ui/configuration/FlightModeConfig.h | 89 -- src/ui/configuration/FlightModeConfig.ui | 276 ----- src/ui/configuration/FrameTypeConfig.cc | 106 -- src/ui/configuration/FrameTypeConfig.h | 55 - src/ui/configuration/FrameTypeConfig.ui | 107 -- src/ui/configuration/GeoFenceConfig.cc | 11 - src/ui/configuration/GeoFenceConfig.h | 19 - src/ui/configuration/GeoFenceConfig.ui | 32 - src/ui/configuration/OpticalFlowConfig.cc | 40 - src/ui/configuration/OpticalFlowConfig.h | 22 - src/ui/configuration/OpticalFlowConfig.ui | 69 -- src/ui/configuration/OsdConfig.cc | 30 - src/ui/configuration/OsdConfig.h | 21 - src/ui/configuration/OsdConfig.ui | 85 -- src/ui/configuration/Radio3DRConfig.cc | 11 - src/ui/configuration/Radio3DRConfig.h | 19 - src/ui/configuration/Radio3DRConfig.ui | 35 - .../configuration/RadioCalibrationConfig.cc | 250 ---- src/ui/configuration/RadioCalibrationConfig.h | 73 -- .../configuration/RadioCalibrationConfig.ui | 280 ----- src/ui/configuration/SonarConfig.cc | 74 -- src/ui/configuration/SonarConfig.h | 23 - src/ui/configuration/SonarConfig.ui | 79 -- src/ui/configuration/StandardParamConfig.cc | 66 - src/ui/configuration/StandardParamConfig.h | 26 - src/ui/configuration/StandardParamConfig.ui | 50 - src/ui/map/QGCMapWidget.cc | 21 - src/ui/map/QGCMapWidget.h | 2 - 97 files changed, 30 insertions(+), 13666 deletions(-) delete mode 100644 src/qgcunittest/FlightModeConfigTest.cc delete mode 100644 src/qgcunittest/FlightModeConfigTest.h delete mode 100644 src/uas/ArduPilotMegaMAV.cc delete mode 100644 src/uas/ArduPilotMegaMAV.h delete mode 100644 src/ui/apmtoolbar.cpp delete mode 100644 src/ui/apmtoolbar.h delete mode 100644 src/ui/configuration/AP2ConfigWidget.cc delete mode 100644 src/ui/configuration/AP2ConfigWidget.h delete mode 100644 src/ui/configuration/AccelCalibrationConfig.cc delete mode 100644 src/ui/configuration/AccelCalibrationConfig.h delete mode 100644 src/ui/configuration/AccelCalibrationConfig.ui delete mode 100644 src/ui/configuration/AdvParameterList.cc delete mode 100644 src/ui/configuration/AdvParameterList.h delete mode 100644 src/ui/configuration/AdvParameterList.ui delete mode 100644 src/ui/configuration/AdvancedParamConfig.cc delete mode 100644 src/ui/configuration/AdvancedParamConfig.h delete mode 100644 src/ui/configuration/AdvancedParamConfig.ui delete mode 100644 src/ui/configuration/AirspeedConfig.cc delete mode 100644 src/ui/configuration/AirspeedConfig.h delete mode 100644 src/ui/configuration/AirspeedConfig.ui delete mode 100644 src/ui/configuration/AntennaTrackerConfig.cc delete mode 100644 src/ui/configuration/AntennaTrackerConfig.h delete mode 100644 src/ui/configuration/AntennaTrackerConfig.ui delete mode 100644 src/ui/configuration/ApmFirmwareConfig.cc delete mode 100644 src/ui/configuration/ApmFirmwareConfig.h delete mode 100644 src/ui/configuration/ApmFirmwareConfig.ui delete mode 100644 src/ui/configuration/ApmHardwareConfig.cc delete mode 100644 src/ui/configuration/ApmHardwareConfig.h delete mode 100644 src/ui/configuration/ApmHardwareConfig.ui delete mode 100644 src/ui/configuration/ApmPlaneLevel.cc delete mode 100644 src/ui/configuration/ApmPlaneLevel.h delete mode 100644 src/ui/configuration/ApmPlaneLevel.ui delete mode 100644 src/ui/configuration/ApmSoftwareConfig.cc delete mode 100644 src/ui/configuration/ApmSoftwareConfig.h delete mode 100644 src/ui/configuration/ApmSoftwareConfig.ui delete mode 100644 src/ui/configuration/ArduCopterPidConfig.cc delete mode 100644 src/ui/configuration/ArduCopterPidConfig.h delete mode 100644 src/ui/configuration/ArduCopterPidConfig.ui delete mode 100644 src/ui/configuration/ArduPlanePidConfig.cc delete mode 100644 src/ui/configuration/ArduPlanePidConfig.h delete mode 100644 src/ui/configuration/ArduPlanePidConfig.ui delete mode 100644 src/ui/configuration/ArduRoverPidConfig.cc delete mode 100644 src/ui/configuration/ArduRoverPidConfig.h delete mode 100644 src/ui/configuration/ArduRoverPidConfig.ui delete mode 100644 src/ui/configuration/BasicPidConfig.cc delete mode 100644 src/ui/configuration/BasicPidConfig.h delete mode 100644 src/ui/configuration/BasicPidConfig.ui delete mode 100644 src/ui/configuration/BatteryMonitorConfig.cc delete mode 100644 src/ui/configuration/BatteryMonitorConfig.h delete mode 100644 src/ui/configuration/BatteryMonitorConfig.ui delete mode 100644 src/ui/configuration/CameraGimbalConfig.cc delete mode 100644 src/ui/configuration/CameraGimbalConfig.h delete mode 100644 src/ui/configuration/CameraGimbalConfig.ui delete mode 100644 src/ui/configuration/CompassConfig.cc delete mode 100644 src/ui/configuration/CompassConfig.h delete mode 100644 src/ui/configuration/CompassConfig.ui delete mode 100644 src/ui/configuration/FailSafeConfig.cc delete mode 100644 src/ui/configuration/FailSafeConfig.h delete mode 100644 src/ui/configuration/FailSafeConfig.ui delete mode 100644 src/ui/configuration/FlightModeConfig.cc delete mode 100644 src/ui/configuration/FlightModeConfig.h delete mode 100644 src/ui/configuration/FlightModeConfig.ui delete mode 100644 src/ui/configuration/FrameTypeConfig.cc delete mode 100644 src/ui/configuration/FrameTypeConfig.h delete mode 100644 src/ui/configuration/FrameTypeConfig.ui delete mode 100644 src/ui/configuration/GeoFenceConfig.cc delete mode 100644 src/ui/configuration/GeoFenceConfig.h delete mode 100644 src/ui/configuration/GeoFenceConfig.ui delete mode 100644 src/ui/configuration/OpticalFlowConfig.cc delete mode 100644 src/ui/configuration/OpticalFlowConfig.h delete mode 100644 src/ui/configuration/OpticalFlowConfig.ui delete mode 100644 src/ui/configuration/OsdConfig.cc delete mode 100644 src/ui/configuration/OsdConfig.h delete mode 100644 src/ui/configuration/OsdConfig.ui delete mode 100644 src/ui/configuration/Radio3DRConfig.cc delete mode 100644 src/ui/configuration/Radio3DRConfig.h delete mode 100644 src/ui/configuration/Radio3DRConfig.ui delete mode 100644 src/ui/configuration/RadioCalibrationConfig.cc delete mode 100644 src/ui/configuration/RadioCalibrationConfig.h delete mode 100644 src/ui/configuration/RadioCalibrationConfig.ui delete mode 100644 src/ui/configuration/SonarConfig.cc delete mode 100644 src/ui/configuration/SonarConfig.h delete mode 100644 src/ui/configuration/SonarConfig.ui delete mode 100644 src/ui/configuration/StandardParamConfig.cc delete mode 100644 src/ui/configuration/StandardParamConfig.h delete mode 100644 src/ui/configuration/StandardParamConfig.ui diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 1e1899568..9977780b0 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -324,38 +324,11 @@ 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 \ @@ -411,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 \ @@ -503,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 \ @@ -538,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 \ @@ -602,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 \ @@ -691,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 \ @@ -726,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 \ @@ -768,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 \ @@ -782,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/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 4a111c53c..4985d9046 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 248f7c84d..de09f956f 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 e9c462483..af12867dd 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/qgcunittest/FlightModeConfigTest.cc b/src/qgcunittest/FlightModeConfigTest.cc deleted file mode 100644 index d0b01ff49..000000000 --- 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 89b5d38f8..000000000 --- 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 e8b61c697..000000000 --- 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 1ff5bf57e..000000000 --- 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 a934e965b..05620ff03 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 d050a3384..9c15a3f21 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/ui/MainWindow.cc b/src/ui/MainWindow.cc index c209145ad..115643343 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 5cfdec60a..96326b820 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 c8c3f1ae1..20ca485eb 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/apmtoolbar.cpp b/src/ui/apmtoolbar.cpp deleted file mode 100644 index 5a4589d2e..000000000 --- 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 5cb93d82c..000000000 --- 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 d48158b32..000000000 --- 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 b8a397dd2..000000000 --- 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 8be791352..000000000 --- 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 152656253..000000000 --- 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 6555a5725..000000000 --- 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 bc0bb6702..000000000 --- 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 6ff55a22f..000000000 --- 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 3b18893d2..000000000 --- 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 8edbe1fd6..000000000 --- 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 07e55d61d..000000000 --- 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 596861a3a..000000000 --- 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 25da75fc2..000000000 --- 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 1646b3675..000000000 --- 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 7d33cae36..000000000 --- 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 6b406da47..000000000 --- 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 35271cb28..000000000 --- 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 f355fc4ca..000000000 --- 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 47e1ac72e..000000000 --- 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 37e7bf40f..000000000 --- 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 4350d71e9..000000000 --- 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 38aef8b6a..000000000 --- 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 427403b6d..000000000 --- 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 e4a711b06..000000000 --- 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 3bda80e92..000000000 --- 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 a6a38078f..000000000 --- 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 ef22b1999..000000000 --- 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 a5308dab7..000000000 --- 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 77b97d082..000000000 --- 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 d3deec752..000000000 --- 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 632d3d17c..000000000 --- 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 d8a1360b8..000000000 --- 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 351ce51ed..000000000 --- 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 13db80b96..000000000 --- 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 3a254cb37..000000000 --- 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 4ee4c406b..000000000 --- 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 026bb8350..000000000 --- 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 214658bdc..000000000 --- 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 47831616e..000000000 --- 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 938940e5f..000000000 --- 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 312923941..000000000 --- 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 4be479c98..000000000 --- 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 ec09c817c..000000000 --- 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 417e6922a..000000000 --- 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 5d11f960a..000000000 --- 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 7d4317e48..000000000 --- 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 9f686243f..000000000 --- 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 1775b5945..000000000 --- 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 411cf79b6..000000000 --- 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 d650c1beb..000000000 --- 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 95b9362b4..000000000 --- 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 f032541b1..000000000 --- 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 824673931..000000000 --- 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 69375dd53..000000000 --- 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 7939fac5b..000000000 --- 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 81ee2939f..000000000 --- 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 9e3a5ae6b..000000000 --- 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 9d8803c26..000000000 --- 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 f52e92369..000000000 --- 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 6787fa5db..000000000 --- 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 ea01a4b24..000000000 --- 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 71624346d..000000000 --- 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 b51ea2e50..000000000 --- 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 89f305582..000000000 --- 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 38b4ae7eb..000000000 --- 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 e5a5bce4c..000000000 --- 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 e3280a9c8..000000000 --- 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 963fa0dd1..000000000 --- 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 6c9e4d7ae..000000000 --- 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 435ae290f..000000000 --- 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 5233921d1..000000000 --- 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 7a98b9dba..000000000 --- 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 0de55857f..000000000 --- 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 00b90f8e2..000000000 --- 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 ccf806211..000000000 --- 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 2826804fb..000000000 --- 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 825591a65..000000000 --- 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 7c40d028c..000000000 --- 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 509a109ee..000000000 --- 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 b098d7d05..000000000 --- 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 53a96d984..000000000 --- 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 99969c492..eda68933c 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 1550c7eff..d290476a7 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 */ -- 2.22.0