From 03af08483138da2268e7622f63739491b4a349f8 Mon Sep 17 00:00:00 2001 From: htramsey Date: Fri, 28 Feb 2025 05:55:10 -0500 Subject: [PATCH 1/2] CMake: Linking Updates --- cmake/CreateWinInstaller.cmake | 2 +- custom-example/qgcimages.qrc | 4 +-- custom-example/qgroundcontrol.qrc | 20 +++++------ qgcimages.qrc | 4 +-- qgroundcontrol.qrc | 20 +++++------ src/AnalyzeView/CMakeLists.txt | 19 +++++++--- src/AutoPilotPlugins/APM/CMakeLists.txt | 2 -- src/AutoPilotPlugins/CMakeLists.txt | 4 +-- src/AutoPilotPlugins/Common/CMakeLists.txt | 33 +++++++++--------- src/AutoPilotPlugins/PX4/CMakeLists.txt | 2 -- src/CMakeLists.txt | 3 -- src/FirmwarePlugin/APM/CMakeLists.txt | 1 - src/FirmwarePlugin/CMakeLists.txt | 3 +- src/FirmwarePlugin/PX4/CMakeLists.txt | 2 +- src/Utilities/Compression/CMakeLists.txt | 5 ++- src/Vehicle/CMakeLists.txt | 1 + src/{ => Vehicle}/VehicleSetup/Bootloader.cc | 0 src/{ => Vehicle}/VehicleSetup/Bootloader.h | 2 ++ src/{ => Vehicle}/VehicleSetup/CMakeLists.txt | 16 ++++----- .../VehicleSetup/FirmwareImage.cc | 0 .../VehicleSetup/FirmwareImage.h | 1 - .../VehicleSetup/FirmwareUpgrade.qml | 0 .../VehicleSetup/FirmwareUpgradeController.cc | 0 .../VehicleSetup/FirmwareUpgradeController.h | 9 ++--- .../VehicleSetup/FirmwareUpgradeIcon.png | Bin .../VehicleSetup/JoystickConfig.qml | 0 .../VehicleSetup/JoystickConfigAdvanced.qml | 0 .../VehicleSetup/JoystickConfigButtons.qml | 0 .../JoystickConfigCalibration.qml | 0 .../VehicleSetup/JoystickConfigController.cc | 0 .../VehicleSetup/JoystickConfigController.h | 6 ++-- .../VehicleSetup/JoystickConfigGeneral.qml | 0 .../VehicleSetup/OpticalFlowSensor.qml | 0 .../VehicleSetup/PX4FirmwareUpgradeThread.cc | 0 .../VehicleSetup/PX4FirmwareUpgradeThread.h | 0 .../VehicleSetup/SetupParameterEditor.qml | 0 src/{ => Vehicle}/VehicleSetup/SetupView.qml | 0 .../VehicleSetup/VehicleSummary.qml | 0 .../VehicleSetup/VehicleSummaryIcon.png | Bin test/AnalyzeView/CMakeLists.txt | 1 + test/AutoPilotPlugins/CMakeLists.txt | 3 +- test/FactSystem/CMakeLists.txt | 2 ++ test/FactSystem/FactSystemTestBase.h | 8 +---- test/FactSystem/FactSystemTestGeneric.h | 9 +---- test/FactSystem/FactSystemTestPX4.h | 9 +---- test/FactSystem/ParameterManagerTest.h | 6 +--- test/FollowMe/CMakeLists.txt | 2 ++ test/MAVLink/StatusTextHandlerTest.cc | 2 +- test/MissionManager/CMakeLists.txt | 7 ++-- .../MissionControllerManagerTest.h | 6 +--- test/MissionManager/MissionControllerTest.h | 6 +--- test/MissionManager/MissionManagerTest.h | 6 +--- test/Utilities/Geo/CMakeLists.txt | 2 +- test/Vehicle/CMakeLists.txt | 6 ++-- test/Vehicle/RequestMessageTest.h | 1 + 55 files changed, 101 insertions(+), 134 deletions(-) rename src/{ => Vehicle}/VehicleSetup/Bootloader.cc (100%) rename src/{ => Vehicle}/VehicleSetup/Bootloader.h (99%) rename src/{ => Vehicle}/VehicleSetup/CMakeLists.txt (84%) rename src/{ => Vehicle}/VehicleSetup/FirmwareImage.cc (100%) rename src/{ => Vehicle}/VehicleSetup/FirmwareImage.h (99%) rename src/{ => Vehicle}/VehicleSetup/FirmwareUpgrade.qml (100%) rename src/{ => Vehicle}/VehicleSetup/FirmwareUpgradeController.cc (100%) rename src/{ => Vehicle}/VehicleSetup/FirmwareUpgradeController.h (99%) rename src/{ => Vehicle}/VehicleSetup/FirmwareUpgradeIcon.png (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfig.qml (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfigAdvanced.qml (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfigButtons.qml (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfigCalibration.qml (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfigController.cc (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfigController.h (100%) rename src/{ => Vehicle}/VehicleSetup/JoystickConfigGeneral.qml (100%) rename src/{ => Vehicle}/VehicleSetup/OpticalFlowSensor.qml (100%) rename src/{ => Vehicle}/VehicleSetup/PX4FirmwareUpgradeThread.cc (100%) rename src/{ => Vehicle}/VehicleSetup/PX4FirmwareUpgradeThread.h (100%) rename src/{ => Vehicle}/VehicleSetup/SetupParameterEditor.qml (100%) rename src/{ => Vehicle}/VehicleSetup/SetupView.qml (100%) rename src/{ => Vehicle}/VehicleSetup/VehicleSummary.qml (100%) rename src/{ => Vehicle}/VehicleSetup/VehicleSummaryIcon.png (100%) diff --git a/cmake/CreateWinInstaller.cmake b/cmake/CreateWinInstaller.cmake index ec5f09cb471..173e0d6db57 100644 --- a/cmake/CreateWinInstaller.cmake +++ b/cmake/CreateWinInstaller.cmake @@ -24,7 +24,7 @@ set(QGC_NSIS_INSTALLER_PARAMETERS /DAPPNAME=QGroundControl /DEXENAME=QGroundControl /DORGNAME=org.mavlink.qgroundcontrol - /DDESTDIR=${CMAKE_BINARY_DIR}/staging + /DDESTDIR=${CMAKE_INSTALL_PREFIX} /NOCD "/XOutFile ${QGC_INSTALLER_OUT}" ${QGC_NSIS_INSTALLER_SCRIPT} diff --git a/custom-example/qgcimages.qrc b/custom-example/qgcimages.qrc index bf24f09cae0..795599b4555 100644 --- a/custom-example/qgcimages.qrc +++ b/custom-example/qgcimages.qrc @@ -86,7 +86,7 @@ ../src/AutoPilotPlugins/PX4/Images/DatalinkLossLight.svg ../src/UI/toolbar/Images/Disarmed.svg ../src/UI/toolbar/Images/Disconnect.svg - ../src/VehicleSetup/FirmwareUpgradeIcon.png + ../src/Vehicle/VehicleSetup/FirmwareUpgradeIcon.png ../src/AutoPilotPlugins/Common/Images/FlightModesComponentIcon.png ../src/AutoPilotPlugins/Common/Images/FlightModesComponentIcon.png ../src/AnalyzeView/FloatingWindow.svg @@ -202,7 +202,7 @@ ../src/AutoPilotPlugins/PX4/Images/VehicleNoseDownRotate.png ../src/AutoPilotPlugins/PX4/Images/VehicleRight.png ../src/AutoPilotPlugins/PX4/Images/VehicleRightRotate.png - ../src/VehicleSetup/VehicleSummaryIcon.png + ../src/Vehicle/VehicleSetup/VehicleSummaryIcon.png ../src/AutoPilotPlugins/PX4/Images/VehicleTailDown.png ../src/AutoPilotPlugins/PX4/Images/VehicleTailDownRotate.png ../src/AutoPilotPlugins/PX4/Images/VehicleUpsideDown.png diff --git a/custom-example/qgroundcontrol.qrc b/custom-example/qgroundcontrol.qrc index 57d510f1eb3..7df3c969b74 100644 --- a/custom-example/qgroundcontrol.qrc +++ b/custom-example/qgroundcontrol.qrc @@ -38,7 +38,7 @@ ../src/UI/preferences/RemoteIDSettings.qml ../src/AutoPilotPlugins/Common/ESP8266Component.qml ../src/AutoPilotPlugins/Common/ESP8266ComponentSummary.qml - ../src/VehicleSetup/FirmwareUpgrade.qml + ../src/Vehicle/VehicleSetup/FirmwareUpgrade.qml ../src/FlightDisplay/QGCVideoBackground.qml ../src/FlightDisplay/FlightDisplayViewDummy.qml ../src/FlightDisplay/FlightDisplayViewUVC.qml @@ -51,11 +51,11 @@ ../src/UI/preferences/HelpSettings.qml ../src/FlightMap/Widgets/IntegratedAttitudeIndicator.qml ../src/FlightMap/Widgets/IntegratedCompassAttitude.qml - ../src/VehicleSetup/JoystickConfig.qml - ../src/VehicleSetup/JoystickConfigAdvanced.qml - ../src/VehicleSetup/JoystickConfigButtons.qml - ../src/VehicleSetup/JoystickConfigCalibration.qml - ../src/VehicleSetup/JoystickConfigGeneral.qml + ../src/Vehicle/VehicleSetup/JoystickConfig.qml + ../src/Vehicle/VehicleSetup/JoystickConfigAdvanced.qml + ../src/Vehicle/VehicleSetup/JoystickConfigButtons.qml + ../src/Vehicle/VehicleSetup/JoystickConfigCalibration.qml + ../src/Vehicle/VehicleSetup/JoystickConfigGeneral.qml ../src/UI/preferences/LinkSettings.qml ../src/AnalyzeView/LogDownloadPage.qml ../src/UI/preferences/LogReplaySettings.qml @@ -74,7 +74,7 @@ ../src/UI/preferences/PlanViewSettings.qml ../src/UI/toolbar/PlanViewToolBar.qml ../src/FlightDisplay/PreFlightCheckList.qml - ../src/VehicleSetup/OpticalFlowSensor.qml + ../src/Vehicle/VehicleSetup/OpticalFlowSensor.qml ../src/FlightMap/Widgets/VerticalCompassAttitude.qml ../src/FlightMap/Widgets/HorizontalCompassAttitude.qml ../src/AnalyzeView/AnalyzePage.qml @@ -283,8 +283,8 @@ ../src/QmlControls/ScreenTools.qml ../src/AutoPilotPlugins/Common/RadioComponent.qml ../src/UI/preferences/SerialSettings.qml - ../src/VehicleSetup/SetupParameterEditor.qml - ../src/VehicleSetup/SetupView.qml + ../src/Vehicle/VehicleSetup/SetupParameterEditor.qml + ../src/Vehicle/VehicleSetup/SetupView.qml ../src/UI/preferences/SettingsPage.qml ../src/UI/SettingsPagesModel.qml ../src/PlanView/SimpleItemEditor.qml @@ -294,7 +294,7 @@ ../src/UI/preferences/TcpSettings.qml ../src/UI/preferences/TelemetrySettings.qml ../src/UI/preferences/UdpSettings.qml - ../src/VehicleSetup/VehicleSummary.qml + ../src/Vehicle/VehicleSetup/VehicleSummary.qml ../src/AnalyzeView/VibrationPage.qml ../src/UI/preferences/VideoSettings.qml ../src/FlightDisplay/VirtualJoystick.qml diff --git a/qgcimages.qrc b/qgcimages.qrc index f6665bb8eb3..716acb55ab5 100644 --- a/qgcimages.qrc +++ b/qgcimages.qrc @@ -86,7 +86,7 @@ src/AutoPilotPlugins/PX4/Images/DatalinkLossLight.svg src/UI/toolbar/Images/Disarmed.svg src/UI/toolbar/Images/Disconnect.svg - src/VehicleSetup/FirmwareUpgradeIcon.png + src/Vehicle/VehicleSetup/FirmwareUpgradeIcon.png src/AutoPilotPlugins/Common/Images/FlightModesComponentIcon.png src/AutoPilotPlugins/Common/Images/FlightModesComponentIcon.png src/AnalyzeView/FloatingWindow.svg @@ -203,7 +203,7 @@ src/AutoPilotPlugins/PX4/Images/VehicleNoseDownRotate.png src/AutoPilotPlugins/PX4/Images/VehicleRight.png src/AutoPilotPlugins/PX4/Images/VehicleRightRotate.png - src/VehicleSetup/VehicleSummaryIcon.png + src/Vehicle/VehicleSetup/VehicleSummaryIcon.png src/AutoPilotPlugins/PX4/Images/VehicleTailDown.png src/AutoPilotPlugins/PX4/Images/VehicleTailDownRotate.png src/AutoPilotPlugins/PX4/Images/VehicleUpsideDown.png diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 24e62fb6665..d5f8a5bd11b 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -38,7 +38,7 @@ src/UI/preferences/RemoteIDSettings.qml src/AutoPilotPlugins/Common/ESP8266Component.qml src/AutoPilotPlugins/Common/ESP8266ComponentSummary.qml - src/VehicleSetup/FirmwareUpgrade.qml + src/Vehicle/VehicleSetup/FirmwareUpgrade.qml src/FlightDisplay/QGCVideoBackground.qml src/FlightDisplay/FlightDisplayViewDummy.qml src/FlightDisplay/FlightDisplayViewUVC.qml @@ -51,11 +51,11 @@ src/UI/preferences/HelpSettings.qml src/FlightMap/Widgets/IntegratedAttitudeIndicator.qml src/FlightMap/Widgets/IntegratedCompassAttitude.qml - src/VehicleSetup/JoystickConfig.qml - src/VehicleSetup/JoystickConfigAdvanced.qml - src/VehicleSetup/JoystickConfigButtons.qml - src/VehicleSetup/JoystickConfigCalibration.qml - src/VehicleSetup/JoystickConfigGeneral.qml + src/Vehicle/VehicleSetup/JoystickConfig.qml + src/Vehicle/VehicleSetup/JoystickConfigAdvanced.qml + src/Vehicle/VehicleSetup/JoystickConfigButtons.qml + src/Vehicle/VehicleSetup/JoystickConfigCalibration.qml + src/Vehicle/VehicleSetup/JoystickConfigGeneral.qml src/UI/preferences/LinkSettings.qml src/AnalyzeView/LogDownloadPage.qml src/UI/preferences/LogReplaySettings.qml @@ -73,7 +73,7 @@ src/UI/preferences/PlanViewSettings.qml src/UI/toolbar/PlanViewToolBar.qml src/FlightDisplay/PreFlightCheckList.qml - src/VehicleSetup/OpticalFlowSensor.qml + src/Vehicle/VehicleSetup/OpticalFlowSensor.qml src/FlightMap/Widgets/VerticalCompassAttitude.qml src/FlightMap/Widgets/HorizontalCompassAttitude.qml src/AnalyzeView/AnalyzePage.qml @@ -294,8 +294,8 @@ src/QmlControls/ScreenTools.qml src/AutoPilotPlugins/Common/RadioComponent.qml src/UI/preferences/SerialSettings.qml - src/VehicleSetup/SetupParameterEditor.qml - src/VehicleSetup/SetupView.qml + src/Vehicle/VehicleSetup/SetupParameterEditor.qml + src/Vehicle/VehicleSetup/SetupView.qml src/UI/preferences/SettingsPage.qml src/UI/SettingsPagesModel.qml src/PlanView/SimpleItemEditor.qml @@ -305,7 +305,7 @@ src/UI/preferences/TcpSettings.qml src/UI/preferences/TelemetrySettings.qml src/UI/preferences/UdpSettings.qml - src/VehicleSetup/VehicleSummary.qml + src/Vehicle/VehicleSetup/VehicleSummary.qml src/AnalyzeView/VibrationPage.qml src/UI/preferences/VideoSettings.qml src/FlightDisplay/VirtualJoystick.qml diff --git a/src/AnalyzeView/CMakeLists.txt b/src/AnalyzeView/CMakeLists.txt index 7f69523888d..8fbb4a1b7dc 100644 --- a/src/AnalyzeView/CMakeLists.txt +++ b/src/AnalyzeView/CMakeLists.txt @@ -117,15 +117,24 @@ CPMAddPackage( "EXPAT_SHARED_LIBS OFF" ) -if(TARGET EXPAT::EXPAT) - set(_EXIV2_ENABLE_XMP ON) -else() - set(_EXIV2_ENABLE_XMP OFF) +set(_EXIV2_ENABLE_XMP OFF) +if(EXPAT_ADDED) + find_package(expat CONFIG QUIET) + if(NOT TARGET expat::expat) + find_package(EXPAT MODULE) + if(EXPAT_FOUND) + if(NOT TARGET expat::expat) + add_library(expat::expat INTERFACE IMPORTED) + target_link_libraries(expat::expat INTERFACE EXPAT::EXPAT) + endif() + set(_EXIV2_ENABLE_XMP ON) + endif() + endif() endif() CPMAddPackage( NAME exiv2 - VERSION 0.28.4 + VERSION 0.28.5 GITHUB_REPOSITORY Exiv2/exiv2 OPTIONS "EXIV2_ENABLE_XMP ${_EXIV2_ENABLE_XMP}" diff --git a/src/AutoPilotPlugins/APM/CMakeLists.txt b/src/AutoPilotPlugins/APM/CMakeLists.txt index 8d4389980b8..1fff924354c 100644 --- a/src/AutoPilotPlugins/APM/CMakeLists.txt +++ b/src/AutoPilotPlugins/APM/CMakeLists.txt @@ -55,10 +55,8 @@ target_link_libraries(APMAutoPilotPlugin Qt6::Core Qt6::Quick AutoPilotPlugins - CommonAutoPilotPlugin FactControls MAVLink - VehicleSetup ) target_include_directories(APMAutoPilotPlugin PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/AutoPilotPlugins/CMakeLists.txt b/src/AutoPilotPlugins/CMakeLists.txt index 6f26e0b2690..ad2ac9adff2 100644 --- a/src/AutoPilotPlugins/CMakeLists.txt +++ b/src/AutoPilotPlugins/CMakeLists.txt @@ -1,4 +1,3 @@ -add_subdirectory(Common) if(NOT QGC_DISABLE_APM_PLUGIN) add_subdirectory(APM) endif() @@ -22,7 +21,6 @@ target_link_libraries(AutoPilotPlugins FirmwarePlugin QGC Vehicle - VehicleSetup PUBLIC Qt6::Core ) @@ -32,3 +30,5 @@ target_include_directories(AutoPilotPlugins ${CMAKE_CURRENT_SOURCE_DIR} Generic ) + +add_subdirectory(Common) diff --git a/src/AutoPilotPlugins/Common/CMakeLists.txt b/src/AutoPilotPlugins/Common/CMakeLists.txt index ea3168cc885..9a485b48590 100644 --- a/src/AutoPilotPlugins/Common/CMakeLists.txt +++ b/src/AutoPilotPlugins/Common/CMakeLists.txt @@ -1,23 +1,23 @@ find_package(Qt6 REQUIRED COMPONENTS Core Network Quick) -qt_add_library(CommonAutoPilotPlugin STATIC - ESP8266Component.cc - ESP8266Component.h - ESP8266ComponentController.cc - ESP8266ComponentController.h - MotorComponent.cc - MotorComponent.h - RadioComponentController.cc - RadioComponentController.h - SyslinkComponent.cc - SyslinkComponent.h - SyslinkComponentController.cc - SyslinkComponentController.h +target_sources(AutoPilotPlugins + PRIVATE + ESP8266Component.cc + ESP8266Component.h + ESP8266ComponentController.cc + ESP8266ComponentController.h + MotorComponent.cc + MotorComponent.h + RadioComponentController.cc + RadioComponentController.h + SyslinkComponent.cc + SyslinkComponent.h + SyslinkComponentController.cc + SyslinkComponentController.h ) -target_link_libraries(CommonAutoPilotPlugin +target_link_libraries(AutoPilotPlugins PRIVATE - AutoPilotPlugins FactSystem QGC Utilities @@ -28,10 +28,9 @@ target_link_libraries(CommonAutoPilotPlugin Qt6::Quick FactControls MAVLink - VehicleSetup ) -target_include_directories(CommonAutoPilotPlugin PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) +target_include_directories(AutoPilotPlugins PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) # file(GLOB QML_SOURCES RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/*.qml) # file(GLOB QML_RESOURCES RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/Images/*.*) diff --git a/src/AutoPilotPlugins/PX4/CMakeLists.txt b/src/AutoPilotPlugins/PX4/CMakeLists.txt index bc6611a324c..31cfe4bcb15 100644 --- a/src/AutoPilotPlugins/PX4/CMakeLists.txt +++ b/src/AutoPilotPlugins/PX4/CMakeLists.txt @@ -46,10 +46,8 @@ target_link_libraries(PX4AutoPilotPlugin Qt6::Core Qt6::Quick AutoPilotPlugins - CommonAutoPilotPlugin FactControls MAVLink - VehicleSetup ) target_include_directories(PX4AutoPilotPlugin PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 38cb1a66acd..22d7f6c2bd3 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -34,7 +34,6 @@ add_subdirectory(Terrain) add_subdirectory(Utilities) add_subdirectory(UTMSP) add_subdirectory(Vehicle) -add_subdirectory(VehicleSetup) add_subdirectory(VideoManager) add_subdirectory(Viewer3D) @@ -54,7 +53,6 @@ target_link_libraries(QGC AutoPilotPlugins Camera Comms - CommonAutoPilotPlugin FactSystem FirmwarePlugin # FirstRunPromptDialogs @@ -74,7 +72,6 @@ target_link_libraries(QGC # UI Utilities Vehicle - VehicleSetup Viewer3D VideoManager PUBLIC diff --git a/src/FirmwarePlugin/APM/CMakeLists.txt b/src/FirmwarePlugin/APM/CMakeLists.txt index 42cac072591..277ad72ec6c 100644 --- a/src/FirmwarePlugin/APM/CMakeLists.txt +++ b/src/FirmwarePlugin/APM/CMakeLists.txt @@ -30,7 +30,6 @@ target_link_libraries(APMFirmwarePlugin Settings Utilities Vehicle - VehicleSetup PUBLIC Qt6::Core Qt6::Network diff --git a/src/FirmwarePlugin/CMakeLists.txt b/src/FirmwarePlugin/CMakeLists.txt index a5337964863..d65bf514e24 100644 --- a/src/FirmwarePlugin/CMakeLists.txt +++ b/src/FirmwarePlugin/CMakeLists.txt @@ -24,11 +24,10 @@ target_link_libraries(FirmwarePlugin PRIVATE AutoPilotPlugins Camera - CommonAutoPilotPlugin MissionManager QGC Utilities - VehicleSetup + Vehicle $<$>:APMFirmwarePlugin> $<$>:PX4FirmwarePlugin> PUBLIC diff --git a/src/FirmwarePlugin/PX4/CMakeLists.txt b/src/FirmwarePlugin/PX4/CMakeLists.txt index bb5389d0124..8bd806fce6e 100644 --- a/src/FirmwarePlugin/PX4/CMakeLists.txt +++ b/src/FirmwarePlugin/PX4/CMakeLists.txt @@ -21,8 +21,8 @@ target_link_libraries(PX4FirmwarePlugin PX4AutoPilotPlugin QGC Settings - VehicleSetup Utilities + Vehicle PUBLIC Qt6::Core FactSystem diff --git a/src/Utilities/Compression/CMakeLists.txt b/src/Utilities/Compression/CMakeLists.txt index 8d123710fa9..78e7207edca 100644 --- a/src/Utilities/Compression/CMakeLists.txt +++ b/src/Utilities/Compression/CMakeLists.txt @@ -23,7 +23,7 @@ target_include_directories(Utilities PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) include(CPM) CPMAddPackage( - NAME ZLIB + NAME zlib VERSION 1.3.1 GITHUB_REPOSITORY madler/zlib OPTIONS @@ -32,10 +32,9 @@ CPMAddPackage( "SKIP_INSTALL_LIBRARIES ON" "SKIP_INSTALL_HEADERS ON" "SKIP_INSTALL_ALL ON" - "ZLIB_USE_STATIC_LIBS ON" ) -if(ZLIB_ADDED) +if(zlib_ADDED) target_link_libraries(Utilities PRIVATE zlibstatic) else() find_package(Qt6ZlibPrivate REQUIRED) diff --git a/src/Vehicle/CMakeLists.txt b/src/Vehicle/CMakeLists.txt index 24c2632c19b..3b5733e1dd0 100644 --- a/src/Vehicle/CMakeLists.txt +++ b/src/Vehicle/CMakeLists.txt @@ -57,3 +57,4 @@ target_include_directories(Vehicle PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) add_subdirectory(Actuators) add_subdirectory(ComponentInformation) add_subdirectory(FactGroups) +add_subdirectory(VehicleSetup) diff --git a/src/VehicleSetup/Bootloader.cc b/src/Vehicle/VehicleSetup/Bootloader.cc similarity index 100% rename from src/VehicleSetup/Bootloader.cc rename to src/Vehicle/VehicleSetup/Bootloader.cc diff --git a/src/VehicleSetup/Bootloader.h b/src/Vehicle/VehicleSetup/Bootloader.h similarity index 99% rename from src/VehicleSetup/Bootloader.h rename to src/Vehicle/VehicleSetup/Bootloader.h index 72ba9e1e037..e883953e35f 100644 --- a/src/VehicleSetup/Bootloader.h +++ b/src/Vehicle/VehicleSetup/Bootloader.h @@ -9,6 +9,8 @@ #pragma once +#include + #ifdef Q_OS_ANDROID #include "qserialport.h" #else diff --git a/src/VehicleSetup/CMakeLists.txt b/src/Vehicle/VehicleSetup/CMakeLists.txt similarity index 84% rename from src/VehicleSetup/CMakeLists.txt rename to src/Vehicle/VehicleSetup/CMakeLists.txt index af5a082fa1c..f3e2b01510d 100644 --- a/src/VehicleSetup/CMakeLists.txt +++ b/src/Vehicle/VehicleSetup/CMakeLists.txt @@ -1,18 +1,18 @@ find_package(Qt6 REQUIRED COMPONENTS Core Gui Qml Quick) -qt_add_library(VehicleSetup STATIC - JoystickConfigController.cc - JoystickConfigController.h +target_sources(Vehicle + PRIVATE + JoystickConfigController.cc + JoystickConfigController.h ) -target_link_libraries(VehicleSetup +target_link_libraries(Vehicle PRIVATE Qt6::Qml FactSystem QGC Settings Utilities - Vehicle PUBLIC Qt6::Core Qt6::Gui @@ -21,10 +21,10 @@ target_link_libraries(VehicleSetup Joystick ) -target_include_directories(VehicleSetup PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) +target_include_directories(Vehicle PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) if(NOT QGC_NO_SERIAL_LINK) - target_sources(VehicleSetup + target_sources(Vehicle PRIVATE Bootloader.cc Bootloader.h @@ -36,7 +36,7 @@ if(NOT QGC_NO_SERIAL_LINK) PX4FirmwareUpgradeThread.h ) - target_link_libraries(VehicleSetup + target_link_libraries(Vehicle PRIVATE API PUBLIC diff --git a/src/VehicleSetup/FirmwareImage.cc b/src/Vehicle/VehicleSetup/FirmwareImage.cc similarity index 100% rename from src/VehicleSetup/FirmwareImage.cc rename to src/Vehicle/VehicleSetup/FirmwareImage.cc diff --git a/src/VehicleSetup/FirmwareImage.h b/src/Vehicle/VehicleSetup/FirmwareImage.h similarity index 99% rename from src/VehicleSetup/FirmwareImage.h rename to src/Vehicle/VehicleSetup/FirmwareImage.h index 72b9f1b1357..e4f87a54749 100644 --- a/src/VehicleSetup/FirmwareImage.h +++ b/src/Vehicle/VehicleSetup/FirmwareImage.h @@ -13,7 +13,6 @@ #pragma once - #include #include #include diff --git a/src/VehicleSetup/FirmwareUpgrade.qml b/src/Vehicle/VehicleSetup/FirmwareUpgrade.qml similarity index 100% rename from src/VehicleSetup/FirmwareUpgrade.qml rename to src/Vehicle/VehicleSetup/FirmwareUpgrade.qml diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.cc similarity index 100% rename from src/VehicleSetup/FirmwareUpgradeController.cc rename to src/Vehicle/VehicleSetup/FirmwareUpgradeController.cc diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.h similarity index 99% rename from src/VehicleSetup/FirmwareUpgradeController.h rename to src/Vehicle/VehicleSetup/FirmwareUpgradeController.h index f86f67d0c63..ef98546c1a8 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.h +++ b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.h @@ -9,17 +9,12 @@ #pragma once -#include "QGCSerialPortInfo.h" - #include #include #include #include -#ifdef Q_OS_ANDROID -#include "qserialportinfo.h" -#else -#include -#endif + +#include "QGCSerialPortInfo.h" class PX4FirmwareUpgradeThread; class PX4FirmwareUpgradeThreadController; diff --git a/src/VehicleSetup/FirmwareUpgradeIcon.png b/src/Vehicle/VehicleSetup/FirmwareUpgradeIcon.png similarity index 100% rename from src/VehicleSetup/FirmwareUpgradeIcon.png rename to src/Vehicle/VehicleSetup/FirmwareUpgradeIcon.png diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/Vehicle/VehicleSetup/JoystickConfig.qml similarity index 100% rename from src/VehicleSetup/JoystickConfig.qml rename to src/Vehicle/VehicleSetup/JoystickConfig.qml diff --git a/src/VehicleSetup/JoystickConfigAdvanced.qml b/src/Vehicle/VehicleSetup/JoystickConfigAdvanced.qml similarity index 100% rename from src/VehicleSetup/JoystickConfigAdvanced.qml rename to src/Vehicle/VehicleSetup/JoystickConfigAdvanced.qml diff --git a/src/VehicleSetup/JoystickConfigButtons.qml b/src/Vehicle/VehicleSetup/JoystickConfigButtons.qml similarity index 100% rename from src/VehicleSetup/JoystickConfigButtons.qml rename to src/Vehicle/VehicleSetup/JoystickConfigButtons.qml diff --git a/src/VehicleSetup/JoystickConfigCalibration.qml b/src/Vehicle/VehicleSetup/JoystickConfigCalibration.qml similarity index 100% rename from src/VehicleSetup/JoystickConfigCalibration.qml rename to src/Vehicle/VehicleSetup/JoystickConfigCalibration.qml diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/Vehicle/VehicleSetup/JoystickConfigController.cc similarity index 100% rename from src/VehicleSetup/JoystickConfigController.cc rename to src/Vehicle/VehicleSetup/JoystickConfigController.cc diff --git a/src/VehicleSetup/JoystickConfigController.h b/src/Vehicle/VehicleSetup/JoystickConfigController.h similarity index 100% rename from src/VehicleSetup/JoystickConfigController.h rename to src/Vehicle/VehicleSetup/JoystickConfigController.h index 29f9943a744..c543ebf8333 100644 --- a/src/VehicleSetup/JoystickConfigController.h +++ b/src/Vehicle/VehicleSetup/JoystickConfigController.h @@ -13,12 +13,12 @@ #pragma once -#include "FactPanelController.h" -#include "Joystick.h" - #include #include +#include "FactPanelController.h" +#include "Joystick.h" + Q_DECLARE_LOGGING_CATEGORY(JoystickConfigControllerLog) class JoystickConfigController : public FactPanelController diff --git a/src/VehicleSetup/JoystickConfigGeneral.qml b/src/Vehicle/VehicleSetup/JoystickConfigGeneral.qml similarity index 100% rename from src/VehicleSetup/JoystickConfigGeneral.qml rename to src/Vehicle/VehicleSetup/JoystickConfigGeneral.qml diff --git a/src/VehicleSetup/OpticalFlowSensor.qml b/src/Vehicle/VehicleSetup/OpticalFlowSensor.qml similarity index 100% rename from src/VehicleSetup/OpticalFlowSensor.qml rename to src/Vehicle/VehicleSetup/OpticalFlowSensor.qml diff --git a/src/VehicleSetup/PX4FirmwareUpgradeThread.cc b/src/Vehicle/VehicleSetup/PX4FirmwareUpgradeThread.cc similarity index 100% rename from src/VehicleSetup/PX4FirmwareUpgradeThread.cc rename to src/Vehicle/VehicleSetup/PX4FirmwareUpgradeThread.cc diff --git a/src/VehicleSetup/PX4FirmwareUpgradeThread.h b/src/Vehicle/VehicleSetup/PX4FirmwareUpgradeThread.h similarity index 100% rename from src/VehicleSetup/PX4FirmwareUpgradeThread.h rename to src/Vehicle/VehicleSetup/PX4FirmwareUpgradeThread.h diff --git a/src/VehicleSetup/SetupParameterEditor.qml b/src/Vehicle/VehicleSetup/SetupParameterEditor.qml similarity index 100% rename from src/VehicleSetup/SetupParameterEditor.qml rename to src/Vehicle/VehicleSetup/SetupParameterEditor.qml diff --git a/src/VehicleSetup/SetupView.qml b/src/Vehicle/VehicleSetup/SetupView.qml similarity index 100% rename from src/VehicleSetup/SetupView.qml rename to src/Vehicle/VehicleSetup/SetupView.qml diff --git a/src/VehicleSetup/VehicleSummary.qml b/src/Vehicle/VehicleSetup/VehicleSummary.qml similarity index 100% rename from src/VehicleSetup/VehicleSummary.qml rename to src/Vehicle/VehicleSetup/VehicleSummary.qml diff --git a/src/VehicleSetup/VehicleSummaryIcon.png b/src/Vehicle/VehicleSetup/VehicleSummaryIcon.png similarity index 100% rename from src/VehicleSetup/VehicleSummaryIcon.png rename to src/Vehicle/VehicleSetup/VehicleSummaryIcon.png diff --git a/test/AnalyzeView/CMakeLists.txt b/test/AnalyzeView/CMakeLists.txt index 4afb2129a73..2160e5ee667 100644 --- a/test/AnalyzeView/CMakeLists.txt +++ b/test/AnalyzeView/CMakeLists.txt @@ -22,6 +22,7 @@ target_link_libraries(AnalyzeViewTest Qt6::Test AnalyzeView MAVLink + MockLink Utilities Vehicle PUBLIC diff --git a/test/AutoPilotPlugins/CMakeLists.txt b/test/AutoPilotPlugins/CMakeLists.txt index eea773e8a11..d08a8a8ddf1 100644 --- a/test/AutoPilotPlugins/CMakeLists.txt +++ b/test/AutoPilotPlugins/CMakeLists.txt @@ -10,12 +10,11 @@ target_link_libraries(AutoPilotPluginsTest PRIVATE Qt6::Test APMAutoPilotPlugin - AutoPilotPlugins - CommonAutoPilotPlugin PX4AutoPilotPlugin Vehicle PUBLIC Qt6::Core + AutoPilotPlugins qgcunittest ) diff --git a/test/FactSystem/CMakeLists.txt b/test/FactSystem/CMakeLists.txt index e89f724b017..d2f1c0a53e2 100644 --- a/test/FactSystem/CMakeLists.txt +++ b/test/FactSystem/CMakeLists.txt @@ -18,9 +18,11 @@ target_link_libraries(FactSystemTest Qt6::Test AutoPilotPlugins FactSystem + MAVLink Settings Vehicle PUBLIC + MockLink qgcunittest ) diff --git a/test/FactSystem/FactSystemTestBase.h b/test/FactSystem/FactSystemTestBase.h index 10e13d0e798..bacfeee6d0c 100644 --- a/test/FactSystem/FactSystemTestBase.h +++ b/test/FactSystem/FactSystemTestBase.h @@ -7,12 +7,7 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - -#ifndef FactSystemTestBase_H -#define FactSystemTestBase_H +#pragma once #include "UnitTest.h" @@ -38,4 +33,3 @@ class FactSystemTestBase : public UnitTest AutoPilotPlugin* _plugin; }; -#endif diff --git a/test/FactSystem/FactSystemTestGeneric.h b/test/FactSystem/FactSystemTestGeneric.h index daa1e7feab5..2a172b5788d 100644 --- a/test/FactSystem/FactSystemTestGeneric.h +++ b/test/FactSystem/FactSystemTestGeneric.h @@ -7,12 +7,7 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - -#ifndef FactSystemTestGeneric_H -#define FactSystemTestGeneric_H +#pragma once #include "FactSystemTestBase.h" @@ -33,5 +28,3 @@ private slots: void qml_test(void) { _qml_test(); } void qmlUpdate_test(void) { _qmlUpdate_test(); } }; - -#endif diff --git a/test/FactSystem/FactSystemTestPX4.h b/test/FactSystem/FactSystemTestPX4.h index 75e74b6c700..b5bd45e6688 100644 --- a/test/FactSystem/FactSystemTestPX4.h +++ b/test/FactSystem/FactSystemTestPX4.h @@ -7,12 +7,7 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - -#ifndef FactSystemTestPX4_H -#define FactSystemTestPX4_H +#pragma once #include "FactSystemTestBase.h" @@ -33,5 +28,3 @@ private slots: void qml_test(void) { _qml_test(); } void qmlUpdate_test(void) { _qmlUpdate_test(); } }; - -#endif diff --git a/test/FactSystem/ParameterManagerTest.h b/test/FactSystem/ParameterManagerTest.h index d04b407e1b2..200c50953a5 100644 --- a/test/FactSystem/ParameterManagerTest.h +++ b/test/FactSystem/ParameterManagerTest.h @@ -7,9 +7,7 @@ * ****************************************************************************/ - -#ifndef ParameterManagerTest_H -#define ParameterManagerTest_H +#pragma once #include "UnitTest.h" #include "MockConfiguration.h" @@ -30,5 +28,3 @@ private slots: private: void _noFailureWorker(MockConfiguration::FailureMode_t failureMode); }; - -#endif diff --git a/test/FollowMe/CMakeLists.txt b/test/FollowMe/CMakeLists.txt index 9d5c020ddca..399093c85ca 100644 --- a/test/FollowMe/CMakeLists.txt +++ b/test/FollowMe/CMakeLists.txt @@ -10,6 +10,8 @@ target_link_libraries(FollowMeTest PRIVATE Qt6::Test FollowMe + PositionManager + Settings Vehicle PUBLIC qgcunittest diff --git a/test/MAVLink/StatusTextHandlerTest.cc b/test/MAVLink/StatusTextHandlerTest.cc index eeea3f5172a..80503115be6 100644 --- a/test/MAVLink/StatusTextHandlerTest.cc +++ b/test/MAVLink/StatusTextHandlerTest.cc @@ -9,7 +9,7 @@ #include "StatusTextHandlerTest.h" #include "StatusTextHandler.h" -#include +#include "MAVLinkLib.h" #include diff --git a/test/MissionManager/CMakeLists.txt b/test/MissionManager/CMakeLists.txt index 31c2170e1c8..e625488b40a 100644 --- a/test/MissionManager/CMakeLists.txt +++ b/test/MissionManager/CMakeLists.txt @@ -29,19 +29,20 @@ qt_add_library(MissionManagerTest target_link_libraries(MissionManagerTest PRIVATE - Qt6::Positioning Qt6::Test API - FactSystem FirmwarePlugin - QmlControls Settings TerrainTest Utilities Vehicle PUBLIC + Qt6::Positioning + FactSystem + MAVLink MissionManager qgcunittest + QmlControls ) target_include_directories(MissionManagerTest PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/test/MissionManager/MissionControllerManagerTest.h b/test/MissionManager/MissionControllerManagerTest.h index 10e1e96a399..517faa1871c 100644 --- a/test/MissionManager/MissionControllerManagerTest.h +++ b/test/MissionManager/MissionControllerManagerTest.h @@ -7,9 +7,7 @@ * ****************************************************************************/ - -#ifndef MissionControllerManagerTest_H -#define MissionControllerManagerTest_H +#pragma once #include "UnitTest.h" #include "MissionManager.h" @@ -74,5 +72,3 @@ protected slots: static const int _missionManagerSignalWaitTime = MissionManager::_ackTimeoutMilliseconds * MissionManager::_maxRetryCount * 2; }; - -#endif diff --git a/test/MissionManager/MissionControllerTest.h b/test/MissionManager/MissionControllerTest.h index 7e8c28a348a..d49a001243e 100644 --- a/test/MissionManager/MissionControllerTest.h +++ b/test/MissionManager/MissionControllerTest.h @@ -7,9 +7,7 @@ * ****************************************************************************/ - -#ifndef MissionControllerTest_H -#define MissionControllerTest_H +#pragma once #include "MissionControllerManagerTest.h" @@ -84,5 +82,3 @@ private slots: const char* _rgMissionControllerSignals[_cMissionControllerSignals]; const char* _rgVisualItemSignals[_cVisualItemSignals]; }; - -#endif diff --git a/test/MissionManager/MissionManagerTest.h b/test/MissionManager/MissionManagerTest.h index 3630ba31e53..de46b2f9103 100644 --- a/test/MissionManager/MissionManagerTest.h +++ b/test/MissionManager/MissionManagerTest.h @@ -7,9 +7,7 @@ * ****************************************************************************/ - -#ifndef MissionManagerTest_H -#define MissionManagerTest_H +#pragma once #include "MissionControllerManagerTest.h" @@ -41,5 +39,3 @@ private slots: static const TestCase_t _rgTestCases[]; static const size_t _cTestCases; }; - -#endif diff --git a/test/Utilities/Geo/CMakeLists.txt b/test/Utilities/Geo/CMakeLists.txt index 512d1c3fd9c..95a403742db 100644 --- a/test/Utilities/Geo/CMakeLists.txt +++ b/test/Utilities/Geo/CMakeLists.txt @@ -8,9 +8,9 @@ target_sources(UtilitiesTest target_link_libraries(UtilitiesTest PRIVATE - Qt6::Positioning Qt6::Test PUBLIC + Qt6::Positioning qgcunittest ) diff --git a/test/Vehicle/CMakeLists.txt b/test/Vehicle/CMakeLists.txt index bbe94e6ba86..a1a5305d8c7 100644 --- a/test/Vehicle/CMakeLists.txt +++ b/test/Vehicle/CMakeLists.txt @@ -21,10 +21,12 @@ qt_add_library(VehicleTest target_link_libraries(VehicleTest PRIVATE Qt6::Test - Comms - Vehicle PUBLIC + Comms + MAVLink + MockLink qgcunittest + Vehicle ) target_include_directories(VehicleTest PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/test/Vehicle/RequestMessageTest.h b/test/Vehicle/RequestMessageTest.h index 3bef4ac8b41..89eccaf8881 100644 --- a/test/Vehicle/RequestMessageTest.h +++ b/test/Vehicle/RequestMessageTest.h @@ -10,6 +10,7 @@ #pragma once #include "UnitTest.h" +#include "MAVLinkLib.h" #include "MockLink.h" #include "Vehicle.h" From bc724b54d886b563dca35450b8b7450d825c030e Mon Sep 17 00:00:00 2001 From: Holden Date: Fri, 21 Feb 2025 22:04:09 -0500 Subject: [PATCH 2/2] AutoPilotPlugins: Cleanup --- src/AutoPilotPlugins/AutoPilotPlugin.cc | 48 +- src/AutoPilotPlugins/AutoPilotPlugin.h | 43 +- .../Common/ESP8266Component.cc | 44 +- .../Common/ESP8266Component.h | 31 +- .../Common/ESP8266ComponentController.cc | 467 ++++++++---------- .../Common/ESP8266ComponentController.h | 146 +++--- src/AutoPilotPlugins/Common/MotorComponent.cc | 43 +- src/AutoPilotPlugins/Common/MotorComponent.h | 28 +- .../Common/RadioComponentController.cc | 436 ++++++++-------- .../Common/RadioComponentController.h | 343 ++++++------- .../Common/SyslinkComponent.cc | 49 +- .../Common/SyslinkComponent.h | 31 +- .../Common/SyslinkComponentController.cc | 128 ++--- .../Common/SyslinkComponentController.h | 61 ++- .../Generic/GenericAutoPilotPlugin.cc | 22 +- .../Generic/GenericAutoPilotPlugin.h | 16 +- src/AutoPilotPlugins/VehicleComponent.cc | 70 ++- src/AutoPilotPlugins/VehicleComponent.h | 82 +-- 18 files changed, 902 insertions(+), 1186 deletions(-) diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index a67050f7675..72d880929c2 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -7,44 +7,43 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - #include "AutoPilotPlugin.h" -#include "QGCApplication.h" #include "FirmwarePlugin.h" +#include "QGCApplication.h" +#include "QGCLoggingCategory.h" #include "Vehicle.h" #include "VehicleComponent.h" + #include -AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) +QGC_LOGGING_CATEGORY(AutoPilotPluginLog, "qgc.autopilotplugin.autopilotplugin"); + +AutoPilotPlugin::AutoPilotPlugin(Vehicle *vehicle, QObject *parent) : QObject(parent) , _vehicle(vehicle) , _firmwarePlugin(vehicle->firmwarePlugin()) - , _setupComplete(false) { - + // qCDebug(AutoPilotPluginLog) << Q_FUNC_INFO << this; } AutoPilotPlugin::~AutoPilotPlugin() { - + // qCDebug(AutoPilotPluginLog) << Q_FUNC_INFO << this; } -void AutoPilotPlugin::_recalcSetupComplete(void) +void AutoPilotPlugin::_recalcSetupComplete() { bool newSetupComplete = true; - for(const QVariant& componentVariant: vehicleComponents()) { - VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); + for (const QVariant &componentVariant : vehicleComponents()) { + const VehicleComponent *const component = qobject_cast(qvariant_cast(componentVariant)); if (component) { if (!component->setupComplete()) { newSetupComplete = false; break; } } else { - qWarning() << "AutoPilotPlugin::_recalcSetupComplete Incorrectly typed VehicleComponent"; + qCWarning(AutoPilotPluginLog) << "Incorrectly typed VehicleComponent"; } } @@ -54,22 +53,17 @@ void AutoPilotPlugin::_recalcSetupComplete(void) } } -bool AutoPilotPlugin::setupComplete(void) const -{ - return _setupComplete; -} - -void AutoPilotPlugin::parametersReadyPreChecks(void) +void AutoPilotPlugin::parametersReadyPreChecks() { _recalcSetupComplete(); // Connect signals in order to keep setupComplete up to date - for(QVariant componentVariant: vehicleComponents()) { - VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); + for (QVariant componentVariant : vehicleComponents()) { + VehicleComponent *const component = qobject_cast(qvariant_cast(componentVariant)); if (component) { - connect(component, &VehicleComponent::setupCompleteChanged, this, &AutoPilotPlugin::_recalcSetupComplete); + (void) connect(component, &VehicleComponent::setupCompleteChanged, this, &AutoPilotPlugin::_recalcSetupComplete); } else { - qWarning() << "AutoPilotPlugin::_recalcSetupComplete Incorrectly typed VehicleComponent"; + qCWarning(AutoPilotPluginLog) << "Incorrectly typed VehicleComponent"; } } @@ -82,12 +76,12 @@ void AutoPilotPlugin::parametersReadyPreChecks(void) } } -VehicleComponent* AutoPilotPlugin::findKnownVehicleComponent(KnownVehicleComponent knownVehicleComponent) +VehicleComponent *AutoPilotPlugin::findKnownVehicleComponent(KnownVehicleComponent knownVehicleComponent) { if (knownVehicleComponent != UnknownVehicleComponent) { - for(const QVariant& componentVariant: vehicleComponents()) { - VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); - if (component && component->KnownVehicleComponent() == knownVehicleComponent) { + for (const QVariant &componentVariant: vehicleComponents()) { + VehicleComponent *const component = qobject_cast(qvariant_cast(componentVariant)); + if (component && (component->KnownVehicleComponent() == knownVehicleComponent)) { return component; } } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 28aef61ec8e..15c2acba8d9 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -9,28 +9,30 @@ #pragma once +#include #include #include #include -class Vehicle; class FirmwarePlugin; +class Vehicle; class VehicleComponent; -/// This is the base class for AutoPilot plugins -/// +Q_DECLARE_LOGGING_CATEGORY(AutoPilotPluginLog) + /// The AutoPilotPlugin class is an abstract base class which represent the methods and objects /// which are specific to a certain AutoPilot. This is the only place where AutoPilot specific /// code should reside in QGroundControl. The remainder of the QGroundControl source is /// generic to a common mavlink implementation. - class AutoPilotPlugin : public QObject { Q_OBJECT + Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents NOTIFY vehicleComponentsChanged) ///< List of VehicleComponent objects + Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged) ///< false: One or more vehicle components require setup public: - AutoPilotPlugin(Vehicle* vehicle, QObject* parent); - ~AutoPilotPlugin(); + explicit AutoPilotPlugin(Vehicle *vehicle, QObject *parent = nullptr); + virtual ~AutoPilotPlugin(); // Vehicle Components which are available for firmware types enum KnownVehicleComponent { @@ -43,35 +45,30 @@ class AutoPilotPlugin : public QObject }; Q_ENUM(KnownVehicleComponent) - Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents NOTIFY vehicleComponentsChanged) ///< List of VehicleComponent objects - Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged) ///< false: One or more vehicle components require setup - /// Called when parameters are ready for the first time. Note that parameters may still be missing. /// Overrides must call base class. - virtual void parametersReadyPreChecks(void); + virtual void parametersReadyPreChecks(); // Must be implemented by derived class - virtual const QVariantList& vehicleComponents(void) = 0; + virtual const QVariantList &vehicleComponents() = 0; /// Returns the name of the vehicle component which must complete setup prior to this one. Empty string for none. - Q_INVOKABLE virtual QString prerequisiteSetup(VehicleComponent* component) const = 0; - - Q_INVOKABLE VehicleComponent* findKnownVehicleComponent(KnownVehicleComponent knownVehicleComponent); + Q_INVOKABLE virtual QString prerequisiteSetup(VehicleComponent *component) const = 0; - Q_INVOKABLE bool knownVehicleComponentAvailable(KnownVehicleComponent knownVehicleComponent) { return findKnownVehicleComponent(knownVehicleComponent) != nullptr; } + Q_INVOKABLE VehicleComponent *findKnownVehicleComponent(KnownVehicleComponent knownVehicleComponent); + Q_INVOKABLE bool knownVehicleComponentAvailable(KnownVehicleComponent knownVehicleComponent) { return (findKnownVehicleComponent(knownVehicleComponent) != nullptr); } - // Property accessors - bool setupComplete(void) const; + bool setupComplete() const { return _setupComplete; } signals: - void setupCompleteChanged (void); - void vehicleComponentsChanged (void); + void setupCompleteChanged(); + void vehicleComponentsChanged(); protected: - Vehicle* _vehicle; - FirmwarePlugin* _firmwarePlugin; - bool _setupComplete; + Vehicle *_vehicle = nullptr; + FirmwarePlugin *_firmwarePlugin = nullptr; + bool _setupComplete = false; private slots: - void _recalcSetupComplete(void); + void _recalcSetupComplete(); }; diff --git a/src/AutoPilotPlugins/Common/ESP8266Component.cc b/src/AutoPilotPlugins/Common/ESP8266Component.cc index 432a2a74f98..708ec419ee9 100644 --- a/src/AutoPilotPlugins/Common/ESP8266Component.cc +++ b/src/AutoPilotPlugins/Common/ESP8266Component.cc @@ -7,53 +7,11 @@ * ****************************************************************************/ - #include "ESP8266Component.h" -#include "AutoPilotPlugin.h" -ESP8266Component::ESP8266Component(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) +ESP8266Component::ESP8266Component(Vehicle *vehicle, AutoPilotPlugin *autopilot, QObject *parent) : VehicleComponent(vehicle, autopilot, AutoPilotPlugin::UnknownVehicleComponent, parent) , _name(tr("WiFi Bridge")) { } - -QString ESP8266Component::name(void) const -{ - return _name; -} - -QString ESP8266Component::description(void) const -{ - return tr("The ESP8266 WiFi Bridge Component is used to setup the WiFi link."); -} - -QString ESP8266Component::iconResource(void) const -{ - return "/qmlimages/wifi.svg"; -} - -bool ESP8266Component::requiresSetup(void) const -{ - return false; -} - -bool ESP8266Component::setupComplete(void) const -{ - return true; -} - -QStringList ESP8266Component::setupCompleteChangedTriggerList(void) const -{ - return QStringList(); -} - -QUrl ESP8266Component::setupSource(void) const -{ - return QUrl::fromUserInput("qrc:/qml/ESP8266Component.qml"); -} - -QUrl ESP8266Component::summaryQmlSource(void) const -{ - return QUrl::fromUserInput("qrc:/qml/ESP8266ComponentSummary.qml"); -} diff --git a/src/AutoPilotPlugins/Common/ESP8266Component.h b/src/AutoPilotPlugins/Common/ESP8266Component.h index 32aa7b7a18f..d042de67eb8 100644 --- a/src/AutoPilotPlugins/Common/ESP8266Component.h +++ b/src/AutoPilotPlugins/Common/ESP8266Component.h @@ -7,7 +7,6 @@ * ****************************************************************************/ - #pragma once #include "VehicleComponent.h" @@ -15,22 +14,20 @@ class ESP8266Component : public VehicleComponent { Q_OBJECT + public: - ESP8266Component (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr); - - // Virtuals from VehicleComponent - QStringList setupCompleteChangedTriggerList() const; - - // Virtuals from VehicleComponent - QString name () const; - QString description () const; - QString iconResource () const; - bool requiresSetup () const; - bool setupComplete () const; - QUrl setupSource () const; - QUrl summaryQmlSource () const; - + explicit ESP8266Component(Vehicle *vehicle, AutoPilotPlugin *autopilot, QObject *parent = nullptr); + + QStringList setupCompleteChangedTriggerList() const final { return QStringList(); } + QString name() const final { return _name; } + QString description() const final { return tr("The ESP8266 WiFi Bridge Component is used to setup the WiFi link."); } + QString iconResource() const final { return QStringLiteral("/qmlimages/wifi.svg"); } + bool requiresSetup() const final { return false; } + bool setupComplete() const final { return true; } + QUrl setupSource() const final { return QUrl::fromUserInput("qrc:/qml/ESP8266Component.qml"); } + QUrl summaryQmlSource() const final { return QUrl::fromUserInput("qrc:/qml/ESP8266ComponentSummary.qml"); } + private: - const QString _name; - QVariantList _summaryItems; + const QString _name; + QVariantList _summaryItems; }; diff --git a/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc b/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc index c0f60bc02d4..ba7444b3f49 100644 --- a/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc +++ b/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc @@ -7,378 +7,319 @@ * ****************************************************************************/ - -/// @file -/// @brief ESP8266 WiFi Config Qml Controller -/// @author Gus Grubba - #include "ESP8266ComponentController.h" #include "ParameterManager.h" -#include "Vehicle.h" #include "QGCLoggingCategory.h" +#include "Vehicle.h" #include -QGC_LOGGING_CATEGORY(ESP8266ComponentControllerLog, "ESP8266ComponentControllerLog") +QGC_LOGGING_CATEGORY(ESP8266ComponentControllerLog, "qgc.autopilotplugins.common.esp8266componentcontroller") #define MAX_RETRIES 5 -//----------------------------------------------------------------------------- -ESP8266ComponentController::ESP8266ComponentController() - : _waitType(WAIT_FOR_NOTHING) - , _retries(0) +ESP8266ComponentController::ESP8266ComponentController(QObject *parent) + : FactPanelController(parent) + , _baud(getParameterFact(componentID(), QStringLiteral("UART_BAUDRATE"))) + , _ver(getParameterFact(componentID(), QStringLiteral("SW_VER"))) + , _ssid1(getParameterFact(componentID(), QStringLiteral("WIFI_SSID1"))) + , _ssid2(getParameterFact(componentID(), QStringLiteral("WIFI_SSID2"))) + , _ssid3(getParameterFact(componentID(), QStringLiteral("WIFI_SSID3"))) + , _ssid4(getParameterFact(componentID(), QStringLiteral("WIFI_SSID4"))) + , _pwd1(getParameterFact(componentID(), QStringLiteral("WIFI_PASSWORD1"))) + , _pwd2(getParameterFact(componentID(), QStringLiteral("WIFI_PASSWORD2"))) + , _pwd3(getParameterFact(componentID(), QStringLiteral("WIFI_PASSWORD3"))) + , _pwd4(getParameterFact(componentID(), QStringLiteral("WIFI_PASSWORD4"))) + , _ssidsta1(getParameterFact(componentID(), QStringLiteral("WIFI_SSIDSTA1"), false)) + , _ssidsta2(getParameterFact(componentID(), QStringLiteral("WIFI_SSIDSTA2"), false)) + , _ssidsta3(getParameterFact(componentID(), QStringLiteral("WIFI_SSIDSTA3"), false)) + , _ssidsta4(getParameterFact(componentID(), QStringLiteral("WIFI_SSIDSTA4"), false)) + , _pwdsta1(getParameterFact(componentID(), QStringLiteral("WIFI_PWDSTA1"), false)) + , _pwdsta2(getParameterFact(componentID(), QStringLiteral("WIFI_PWDSTA2"), false)) + , _pwdsta3(getParameterFact(componentID(), QStringLiteral("WIFI_PWDSTA3"), false)) + , _pwdsta4(getParameterFact(componentID(), QStringLiteral("WIFI_PWDSTA4"), false)) { - for(int i = 1; i < 12; i++) { + // qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this; + + for (int i = 1; i < 12; i++) { _channels.append(QString::number(i)); } - _baudRates.append(QStringLiteral("57600")); - _baudRates.append(QStringLiteral("115200")); - _baudRates.append(QStringLiteral("230400")); - _baudRates.append(QStringLiteral("460800")); - _baudRates.append(QStringLiteral("921600")); - connect(_vehicle, &Vehicle::mavCommandResult, this, &ESP8266ComponentController::_mavCommandResult); - Fact* ssid = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID4")); - connect(ssid, &Fact::valueChanged, this, &ESP8266ComponentController::_ssidChanged); - Fact* paswd = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD4")); - connect(paswd, &Fact::valueChanged, this, &ESP8266ComponentController::_passwordChanged); - Fact* baud = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("UART_BAUDRATE")); - connect(baud, &Fact::valueChanged, this, &ESP8266ComponentController::_baudChanged); - Fact* ver = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("SW_VER")); - connect(ver, &Fact::valueChanged, this, &ESP8266ComponentController::_versionChanged); -} - -//----------------------------------------------------------------------------- -ESP8266ComponentController::~ESP8266ComponentController() -{ + (void) connect(_vehicle, &Vehicle::mavCommandResult, this, &ESP8266ComponentController::_mavCommandResult); + (void) connect(_ssid4, &Fact::valueChanged, this, &ESP8266ComponentController::_ssidChanged); + (void) connect(_pwd4, &Fact::valueChanged, this, &ESP8266ComponentController::_passwordChanged); + (void) connect(_baud, &Fact::valueChanged, this, &ESP8266ComponentController::_baudChanged); + (void) connect(_ver, &Fact::valueChanged, this, &ESP8266ComponentController::_versionChanged); } -int ESP8266ComponentController::componentID() +ESP8266ComponentController::~ESP8266ComponentController() { - return MAV_COMP_ID_UDP_BRIDGE; + // qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this; } -//----------------------------------------------------------------------------- -QString -ESP8266ComponentController::version() +QString ESP8266ComponentController::version() const { - uint32_t uv = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("SW_VER"))->rawValue().toUInt(); - QString versionString = QString("%1.%2.%3").arg(uv >> 24).arg((uv >> 16) & 0xFF).arg(uv & 0xFFFF); + const uint32_t uv = getParameterFact(componentID(), QStringLiteral("SW_VER"))->rawValue().toUInt(); + const QString versionString = QStringLiteral("%1.%2.%3").arg(uv >> 24).arg((uv >> 16) & 0xFF).arg(uv & 0xFFFF); return versionString; } -//----------------------------------------------------------------------------- -QString -ESP8266ComponentController::wifiIPAddress() +QString ESP8266ComponentController::wifiIPAddress() { - if(_ipAddress.isEmpty()) { - if(parameterExists(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_IPADDRESS"))) { - QHostAddress address(qFromBigEndian(getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_IPADDRESS"))->rawValue().toUInt())); + if (_ipAddress.isEmpty()) { + if (parameterExists(componentID(), QStringLiteral("WIFI_IPADDRESS"))) { + const QHostAddress address(qFromBigEndian(getParameterFact(componentID(), QStringLiteral("WIFI_IPADDRESS"))->rawValue().toUInt())); _ipAddress = address.toString(); } else { - _ipAddress = "192.168.4.1"; + _ipAddress = QStringLiteral("192.168.4.1"); } } + return _ipAddress; } -//----------------------------------------------------------------------------- -QString -ESP8266ComponentController::wifiSSID() +QString ESP8266ComponentController::wifiSSID() const { - uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID1"))->rawValue().toUInt(); - uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID2"))->rawValue().toUInt(); - uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID3"))->rawValue().toUInt(); - uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID4"))->rawValue().toUInt(); + const uint32_t s1 = _ssid1->rawValue().toUInt(); + const uint32_t s2 = _ssid2->rawValue().toUInt(); + const uint32_t s3 = _ssid3->rawValue().toUInt(); + const uint32_t s4 = _ssid4->rawValue().toUInt(); + char tmp[20]; - memcpy(&tmp[0], &s1, sizeof(uint32_t)); - memcpy(&tmp[4], &s2, sizeof(uint32_t)); - memcpy(&tmp[8], &s3, sizeof(uint32_t)); - memcpy(&tmp[12], &s4, sizeof(uint32_t)); + (void) memcpy(&tmp[0], &s1, sizeof(uint32_t)); + (void) memcpy(&tmp[4], &s2, sizeof(uint32_t)); + (void) memcpy(&tmp[8], &s3, sizeof(uint32_t)); + (void) memcpy(&tmp[12], &s4, sizeof(uint32_t)); + return QString(tmp); } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::setWifiSSID(QString ssid) +void ESP8266ComponentController::setWifiSSID(const QString &ssid) const { char tmp[20]; - memset(tmp, 0, sizeof(tmp)); - std::string sid = ssid.toStdString(); - strncpy(tmp, sid.c_str(), sizeof(tmp)); - Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID1")); - Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID2")); - Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID3")); - Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSID4")); + (void) memset(tmp, 0, sizeof(tmp)); + const std::string sid = ssid.toStdString(); + (void) strncpy(tmp, sid.c_str(), sizeof(tmp)); + uint32_t u; - memcpy(&u, &tmp[0], sizeof(uint32_t)); - f1->setRawValue(QVariant(u)); - memcpy(&u, &tmp[4], sizeof(uint32_t)); - f2->setRawValue(QVariant(u)); - memcpy(&u, &tmp[8], sizeof(uint32_t)); - f3->setRawValue(QVariant(u)); - memcpy(&u, &tmp[12], sizeof(uint32_t)); - f4->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[0], sizeof(uint32_t)); + _ssid1->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[4], sizeof(uint32_t)); + _ssid2->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[8], sizeof(uint32_t)); + _ssid3->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[12], sizeof(uint32_t)); + _ssid4->setRawValue(QVariant(u)); } -//----------------------------------------------------------------------------- -QString -ESP8266ComponentController::wifiPassword() +QString ESP8266ComponentController::wifiPassword() const { - uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD1"))->rawValue().toUInt(); - uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD2"))->rawValue().toUInt(); - uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD3"))->rawValue().toUInt(); - uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD4"))->rawValue().toUInt(); + const uint32_t s1 = _pwd1->rawValue().toUInt(); + const uint32_t s2 = _pwd2->rawValue().toUInt(); + const uint32_t s3 = _pwd3->rawValue().toUInt(); + const uint32_t s4 = _pwd4->rawValue().toUInt(); + char tmp[20]; - memcpy(&tmp[0], &s1, sizeof(uint32_t)); - memcpy(&tmp[4], &s2, sizeof(uint32_t)); - memcpy(&tmp[8], &s3, sizeof(uint32_t)); - memcpy(&tmp[12], &s4, sizeof(uint32_t)); + (void) memcpy(&tmp[0], &s1, sizeof(uint32_t)); + (void) memcpy(&tmp[4], &s2, sizeof(uint32_t)); + (void) memcpy(&tmp[8], &s3, sizeof(uint32_t)); + (void) memcpy(&tmp[12], &s4, sizeof(uint32_t)); + return QString(tmp); } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::setWifiPassword(QString password) +void ESP8266ComponentController::setWifiPassword(const QString &password) const { char tmp[20]; - memset(tmp, 0, sizeof(tmp)); - std::string pwd = password.toStdString(); - strncpy(tmp, pwd.c_str(), sizeof(tmp)); - Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD1")); - Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD2")); - Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD3")); - Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PASSWORD4")); + (void) memset(tmp, 0, sizeof(tmp)); + const std::string pwd = password.toStdString(); + (void) strncpy(tmp, pwd.c_str(), sizeof(tmp)); + uint32_t u; - memcpy(&u, &tmp[0], sizeof(uint32_t)); - f1->setRawValue(QVariant(u)); - memcpy(&u, &tmp[4], sizeof(uint32_t)); - f2->setRawValue(QVariant(u)); - memcpy(&u, &tmp[8], sizeof(uint32_t)); - f3->setRawValue(QVariant(u)); - memcpy(&u, &tmp[12], sizeof(uint32_t)); - f4->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[0], sizeof(uint32_t)); + _pwd1->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[4], sizeof(uint32_t)); + _pwd2->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[8], sizeof(uint32_t)); + _pwd3->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[12], sizeof(uint32_t)); + _pwd4->setRawValue(QVariant(u)); } -//----------------------------------------------------------------------------- -QString -ESP8266ComponentController::wifiSSIDSta() +QString ESP8266ComponentController::wifiSSIDSta() const { - if(!parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA1")) { + if (!parameterExists(componentID(), "WIFI_SSIDSTA1")) { return QString(); } - uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA1"))->rawValue().toUInt(); - uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA2"))->rawValue().toUInt(); - uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA3"))->rawValue().toUInt(); - uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA4"))->rawValue().toUInt(); + + const uint32_t s1 = _ssidsta1->rawValue().toUInt(); + const uint32_t s2 = _ssidsta2->rawValue().toUInt(); + const uint32_t s3 = _ssidsta3->rawValue().toUInt(); + const uint32_t s4 = _ssidsta4->rawValue().toUInt(); + char tmp[20]; - memcpy(&tmp[0], &s1, sizeof(uint32_t)); - memcpy(&tmp[4], &s2, sizeof(uint32_t)); - memcpy(&tmp[8], &s3, sizeof(uint32_t)); - memcpy(&tmp[12], &s4, sizeof(uint32_t)); + (void) memcpy(&tmp[0], &s1, sizeof(uint32_t)); + (void) memcpy(&tmp[4], &s2, sizeof(uint32_t)); + (void) memcpy(&tmp[8], &s3, sizeof(uint32_t)); + (void) memcpy(&tmp[12], &s4, sizeof(uint32_t)); + return QString(tmp); } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::setWifiSSIDSta(QString ssid) +void ESP8266ComponentController::setWifiSSIDSta(const QString &ssid) const { - if(parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA1")) { - char tmp[20]; - memset(tmp, 0, sizeof(tmp)); - std::string sid = ssid.toStdString(); - strncpy(tmp, sid.c_str(), sizeof(tmp)); - Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA1")); - Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA2")); - Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA3")); - Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_SSIDSTA4")); - uint32_t u; - memcpy(&u, &tmp[0], sizeof(uint32_t)); - f1->setRawValue(QVariant(u)); - memcpy(&u, &tmp[4], sizeof(uint32_t)); - f2->setRawValue(QVariant(u)); - memcpy(&u, &tmp[8], sizeof(uint32_t)); - f3->setRawValue(QVariant(u)); - memcpy(&u, &tmp[12], sizeof(uint32_t)); - f4->setRawValue(QVariant(u)); + if (!parameterExists(componentID(), "WIFI_SSIDSTA1")) { + return; } + + char tmp[20]; + (void) memset(tmp, 0, sizeof(tmp)); + const std::string sid = ssid.toStdString(); + (void) strncpy(tmp, sid.c_str(), sizeof(tmp)); + + uint32_t u; + (void) memcpy(&u, &tmp[0], sizeof(uint32_t)); + _ssidsta1->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[4], sizeof(uint32_t)); + _ssidsta2->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[8], sizeof(uint32_t)); + _ssidsta3->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[12], sizeof(uint32_t)); + _ssidsta4->setRawValue(QVariant(u)); } -//----------------------------------------------------------------------------- -QString -ESP8266ComponentController::wifiPasswordSta() +QString ESP8266ComponentController::wifiPasswordSta() const { - if(!parameterExists(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA1"))) { + if (!parameterExists(componentID(), QStringLiteral("WIFI_PWDSTA1"))) { return QString(); } - uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA1"))->rawValue().toUInt(); - uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA2"))->rawValue().toUInt(); - uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA3"))->rawValue().toUInt(); - uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA4"))->rawValue().toUInt(); + + const uint32_t s1 = _pwdsta1->rawValue().toUInt(); + const uint32_t s2 = _pwdsta2->rawValue().toUInt(); + const uint32_t s3 = _pwdsta3->rawValue().toUInt(); + const uint32_t s4 = _pwdsta4->rawValue().toUInt(); + char tmp[20]; - memcpy(&tmp[0], &s1, sizeof(uint32_t)); - memcpy(&tmp[4], &s2, sizeof(uint32_t)); - memcpy(&tmp[8], &s3, sizeof(uint32_t)); - memcpy(&tmp[12], &s4, sizeof(uint32_t)); + (void) memcpy(&tmp[0], &s1, sizeof(uint32_t)); + (void) memcpy(&tmp[4], &s2, sizeof(uint32_t)); + (void) memcpy(&tmp[8], &s3, sizeof(uint32_t)); + (void) memcpy(&tmp[12], &s4, sizeof(uint32_t)); + return QString(tmp); } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::setWifiPasswordSta(QString password) +void ESP8266ComponentController::setWifiPasswordSta(const QString &password) const { - if(parameterExists(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA1"))) { - char tmp[20]; - memset(tmp, 0, sizeof(tmp)); - std::string pwd = password.toStdString(); - strncpy(tmp, pwd.c_str(), sizeof(tmp)); - Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA1")); - Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA2")); - Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA3")); - Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("WIFI_PWDSTA4")); - uint32_t u; - memcpy(&u, &tmp[0], sizeof(uint32_t)); - f1->setRawValue(QVariant(u)); - memcpy(&u, &tmp[4], sizeof(uint32_t)); - f2->setRawValue(QVariant(u)); - memcpy(&u, &tmp[8], sizeof(uint32_t)); - f3->setRawValue(QVariant(u)); - memcpy(&u, &tmp[12], sizeof(uint32_t)); - f4->setRawValue(QVariant(u)); + if (!parameterExists(componentID(), QStringLiteral("WIFI_PWDSTA1"))) { + return; } + + char tmp[20]; + (void) memset(tmp, 0, sizeof(tmp)); + const std::string pwd = password.toStdString(); + (void) strncpy(tmp, pwd.c_str(), sizeof(tmp)); + + uint32_t u; + (void) memcpy(&u, &tmp[0], sizeof(uint32_t)); + _pwdsta1->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[4], sizeof(uint32_t)); + _pwdsta2->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[8], sizeof(uint32_t)); + _pwdsta3->setRawValue(QVariant(u)); + (void) memcpy(&u, &tmp[12], sizeof(uint32_t)); + _pwdsta4->setRawValue(QVariant(u)); } -//----------------------------------------------------------------------------- -int -ESP8266ComponentController::baudIndex() +int ESP8266ComponentController::baudIndex() const { - int b = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("UART_BAUDRATE"))->rawValue().toInt(); + const int b = getParameterFact(componentID(), QStringLiteral("UART_BAUDRATE"))->rawValue().toInt(); switch (b) { - case 57600: - return 0; - case 115200: - return 1; - case 230400: - return 2; - case 460800: - return 3; - case 921600: - default: - return 4; + case 57600: + return 0; + case 115200: + return 1; + case 230400: + return 2; + case 460800: + return 3; + case 921600: + default: + return 4; } } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::setBaudIndex(int idx) +void ESP8266ComponentController::setBaudIndex(int idx) const { - if(idx >= 0 && idx != baudIndex()) { + if ((idx >= 0) && (idx != baudIndex())) { int baud = 921600; switch(idx) { - case 0: - baud = 57600; - break; - case 1: - baud = 115200; - break; - case 2: - baud = 230400; - break; - case 3: - baud = 460800; - break; - default: - baud = 921600; + case 0: + baud = 57600; + break; + case 1: + baud = 115200; + break; + case 2: + baud = 230400; + break; + case 3: + baud = 460800; + break; + default: + baud = 921600; } - Fact* b = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, QStringLiteral("UART_BAUDRATE")); - b->setRawValue(baud); + _baud->setRawValue(baud); } } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::reboot() +void ESP8266ComponentController::reboot() { _waitType = WAIT_FOR_REBOOT; emit busyChanged(); - _retries = MAX_RETRIES; + _retries = MAX_RETRIES; _reboot(); } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::restoreDefaults() +void ESP8266ComponentController::restoreDefaults() { _waitType = WAIT_FOR_RESTORE; emit busyChanged(); - _retries = MAX_RETRIES; + _retries = MAX_RETRIES; _restoreDefaults(); } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_reboot() +void ESP8266ComponentController::_reboot() const { - _vehicle->sendMavCommand(MAV_COMP_ID_UDP_BRIDGE, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true /* showError */, 0.0f, 1.0f); + _vehicle->sendMavCommand(componentID(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true /* showError */, 0.0f, 1.0f); qCDebug(ESP8266ComponentControllerLog) << "_reboot()"; } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_restoreDefaults() +void ESP8266ComponentController::_restoreDefaults() const { - _vehicle->sendMavCommand(MAV_COMP_ID_UDP_BRIDGE, MAV_CMD_PREFLIGHT_STORAGE, true /* showError */, 2.0f); + _vehicle->sendMavCommand(componentID(), MAV_CMD_PREFLIGHT_STORAGE, true /* showError */, 2.0f); qCDebug(ESP8266ComponentControllerLog) << "_restoreDefaults()"; } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle) +void ESP8266ComponentController::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle) { Q_UNUSED(vehicleId); Q_UNUSED(noReponseFromVehicle); - if (component == MAV_COMP_ID_UDP_BRIDGE) { - if (result != MAV_RESULT_ACCEPTED) { - qWarning() << "ESP8266ComponentController command" << command << "rejected."; - return; - } - if ((_waitType == WAIT_FOR_REBOOT && command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) || - (_waitType == WAIT_FOR_RESTORE && command == MAV_CMD_PREFLIGHT_STORAGE)) { - _waitType = WAIT_FOR_NOTHING; - emit busyChanged(); - qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command; - if (command == MAV_CMD_PREFLIGHT_STORAGE) { - _vehicle->parameterManager()->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE); - } - } + if (component != componentID()) { + return; } -} -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_ssidChanged(QVariant) -{ - emit wifiSSIDChanged(); -} - -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_passwordChanged(QVariant) -{ - emit wifiPasswordChanged(); -} - -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_baudChanged(QVariant) -{ - emit baudIndexChanged(); -} + if (result != MAV_RESULT_ACCEPTED) { + qCWarning(ESP8266ComponentControllerLog) << "ESP8266ComponentController command" << command << "rejected."; + return; + } -//----------------------------------------------------------------------------- -void -ESP8266ComponentController::_versionChanged(QVariant) -{ - emit versionChanged(); + if (((_waitType == WAIT_FOR_REBOOT) && (command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN)) || ((_waitType == WAIT_FOR_RESTORE) && (command == MAV_CMD_PREFLIGHT_STORAGE))) { + _waitType = WAIT_FOR_NOTHING; + emit busyChanged(); + qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command; + if (command == MAV_CMD_PREFLIGHT_STORAGE) { + _vehicle->parameterManager()->refreshAllParameters(componentID()); + } + } } diff --git a/src/AutoPilotPlugins/Common/ESP8266ComponentController.h b/src/AutoPilotPlugins/Common/ESP8266ComponentController.h index f837f0a86e6..4cabaadeb69 100644 --- a/src/AutoPilotPlugins/Common/ESP8266ComponentController.h +++ b/src/AutoPilotPlugins/Common/ESP8266ComponentController.h @@ -7,94 +7,85 @@ * ****************************************************************************/ - - -/// @file -/// @brief ESP8266 WiFi Config Qml Controller -/// @author Gus Grubba - #pragma once -#include "FactPanelController.h" - #include +#include + +#include "FactPanelController.h" +#include "MAVLinkLib.h" Q_DECLARE_LOGGING_CATEGORY(ESP8266ComponentControllerLog) +class Fact; class Vehicle; -namespace Ui { - class ESP8266ComponentController; -} - class ESP8266ComponentController : public FactPanelController { Q_OBJECT Q_MOC_INCLUDE("Vehicle.h") + Q_PROPERTY(int componentID READ componentID CONSTANT) + Q_PROPERTY(QString version READ version NOTIFY versionChanged) + Q_PROPERTY(QString wifiIPAddress READ wifiIPAddress CONSTANT) + Q_PROPERTY(QString wifiSSID READ wifiSSID WRITE setWifiSSID NOTIFY wifiSSIDChanged) + Q_PROPERTY(QString wifiPassword READ wifiPassword WRITE setWifiPassword NOTIFY wifiPasswordChanged) + Q_PROPERTY(QString wifiSSIDSta READ wifiSSIDSta WRITE setWifiSSIDSta NOTIFY wifiSSIDStaChanged) + Q_PROPERTY(QString wifiPasswordSta READ wifiPasswordSta WRITE setWifiPasswordSta NOTIFY wifiPasswordStaChanged) + Q_PROPERTY(QStringList wifiChannels READ wifiChannels CONSTANT) + Q_PROPERTY(QStringList baudRates READ baudRates CONSTANT) + Q_PROPERTY(int baudIndex READ baudIndex WRITE setBaudIndex NOTIFY baudIndexChanged) + Q_PROPERTY(bool busy READ busy NOTIFY busyChanged) + Q_PROPERTY(Vehicle *vehicle READ vehicle CONSTANT) public: - ESP8266ComponentController (); - ~ESP8266ComponentController (); - - Q_PROPERTY(int componentID READ componentID CONSTANT) - Q_PROPERTY(QString version READ version NOTIFY versionChanged) - Q_PROPERTY(QString wifiIPAddress READ wifiIPAddress CONSTANT) - Q_PROPERTY(QString wifiSSID READ wifiSSID WRITE setWifiSSID NOTIFY wifiSSIDChanged) - Q_PROPERTY(QString wifiPassword READ wifiPassword WRITE setWifiPassword NOTIFY wifiPasswordChanged) - Q_PROPERTY(QString wifiSSIDSta READ wifiSSIDSta WRITE setWifiSSIDSta NOTIFY wifiSSIDStaChanged) - Q_PROPERTY(QString wifiPasswordSta READ wifiPasswordSta WRITE setWifiPasswordSta NOTIFY wifiPasswordStaChanged) - Q_PROPERTY(QStringList wifiChannels READ wifiChannels CONSTANT) - Q_PROPERTY(QStringList baudRates READ baudRates CONSTANT) - Q_PROPERTY(int baudIndex READ baudIndex WRITE setBaudIndex NOTIFY baudIndexChanged) - Q_PROPERTY(bool busy READ busy NOTIFY busyChanged) - Q_PROPERTY(Vehicle* vehicle READ vehicle CONSTANT) + explicit ESP8266ComponentController(QObject *parent = nullptr); + ~ESP8266ComponentController(); Q_INVOKABLE void restoreDefaults(); - Q_INVOKABLE void reboot (); - - int componentID (); - QString version (); - QString wifiIPAddress (); - QString wifiSSID (); - QString wifiPassword (); - QString wifiSSIDSta (); - QString wifiPasswordSta (); - QStringList wifiChannels () { return _channels; } - QStringList baudRates () { return _baudRates; } - int baudIndex (); - bool busy () const{ return _waitType != WAIT_FOR_NOTHING; } - Vehicle* vehicle () { return _vehicle; } - - void setWifiSSID (QString id); - void setWifiPassword (QString pwd); - void setWifiSSIDSta (QString id); - void setWifiPasswordSta (QString pwd); - void setBaudIndex (int idx); + Q_INVOKABLE void reboot(); + + static int componentID() { return MAV_COMP_ID_UDP_BRIDGE; } + QString version() const; + QString wifiIPAddress(); + QString wifiSSID() const; + QString wifiPassword() const; + QString wifiSSIDSta() const; + QString wifiPasswordSta() const; + QStringList wifiChannels() const { return _channels; } + QStringList baudRates() const { return _baudRates; } + int baudIndex() const; + bool busy() const { return (_waitType != WAIT_FOR_NOTHING); } + Vehicle *vehicle() const { return _vehicle; } + + void setWifiSSID(const QString &id) const; + void setWifiPassword(const QString &pwd) const; + void setWifiSSIDSta(const QString &id) const; + void setWifiPasswordSta(const QString &pwd) const; + void setBaudIndex(int idx) const; signals: - void versionChanged (); - void wifiSSIDChanged (); - void wifiPasswordChanged (); - void wifiSSIDStaChanged (); - void wifiPasswordStaChanged (); - void baudIndexChanged (); - void busyChanged (); + void versionChanged(); + void wifiSSIDChanged(); + void wifiPasswordChanged(); + void wifiSSIDStaChanged(); + void wifiPasswordStaChanged(); + void baudIndexChanged(); + void busyChanged(); private slots: - void _mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle); - void _ssidChanged (QVariant value); - void _passwordChanged (QVariant value); - void _baudChanged (QVariant value); - void _versionChanged (QVariant value); + void _mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle); + void _ssidChanged(QVariant value) { emit wifiSSIDChanged(); } + void _passwordChanged(QVariant value) { emit wifiPasswordChanged(); } + void _baudChanged(QVariant value) { emit baudIndexChanged(); } + void _versionChanged(QVariant value) { emit versionChanged(); } private: - void _reboot (); - void _restoreDefaults (); + void _reboot() const; + void _restoreDefaults() const; -private: QStringList _channels; - QStringList _baudRates; - QString _ipAddress; + const QStringList _baudRates = { QStringLiteral("57600"), QStringLiteral("115200"), QStringLiteral("230400"), QStringLiteral("460800"), QStringLiteral("921600") }; + QString _ipAddress; enum { WAIT_FOR_NOTHING, @@ -102,6 +93,29 @@ private slots: WAIT_FOR_RESTORE }; - int _waitType; - int _retries; + int _waitType = WAIT_FOR_NOTHING; + int _retries = 0; + + Fact *_baud = nullptr; + Fact *_ver = nullptr; + + Fact *_ssid1 = nullptr; + Fact *_ssid2 = nullptr; + Fact *_ssid3 = nullptr; + Fact *_ssid4 = nullptr; + + Fact *_pwd1 = nullptr; + Fact *_pwd2 = nullptr; + Fact *_pwd3 = nullptr; + Fact *_pwd4 = nullptr; + + Fact *_ssidsta1 = nullptr; + Fact *_ssidsta2 = nullptr; + Fact *_ssidsta3 = nullptr; + Fact *_ssidsta4 = nullptr; + + Fact *_pwdsta1 = nullptr; + Fact *_pwdsta2 = nullptr; + Fact *_pwdsta3 = nullptr; + Fact *_pwdsta4 = nullptr; }; diff --git a/src/AutoPilotPlugins/Common/MotorComponent.cc b/src/AutoPilotPlugins/Common/MotorComponent.cc index 6377e32e233..b6b5292b0b8 100644 --- a/src/AutoPilotPlugins/Common/MotorComponent.cc +++ b/src/AutoPilotPlugins/Common/MotorComponent.cc @@ -8,51 +8,10 @@ ****************************************************************************/ #include "MotorComponent.h" -#include "AutoPilotPlugin.h" -MotorComponent::MotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) +MotorComponent::MotorComponent(Vehicle *vehicle, AutoPilotPlugin *autopilot, QObject *parent) : VehicleComponent(vehicle, autopilot, AutoPilotPlugin::UnknownVehicleComponent, parent) , _name(tr("Motors")) { } - -QString MotorComponent::name(void) const -{ - return _name; -} - -QString MotorComponent::description(void) const -{ - return tr("Motors Setup is used to manually test motor control and direction."); -} - -QString MotorComponent::iconResource(void) const -{ - return QStringLiteral("/qmlimages/MotorComponentIcon.svg"); -} - -bool MotorComponent::requiresSetup(void) const -{ - return false; -} - -bool MotorComponent::setupComplete(void) const -{ - return true; -} - -QStringList MotorComponent::setupCompleteChangedTriggerList(void) const -{ - return QStringList(); -} - -QUrl MotorComponent::setupSource(void) const -{ - return QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/Controls/MotorComponent.qml")); -} - -QUrl MotorComponent::summaryQmlSource(void) const -{ - return QUrl(); -} diff --git a/src/AutoPilotPlugins/Common/MotorComponent.h b/src/AutoPilotPlugins/Common/MotorComponent.h index a3a56df1c4f..ca0ede84344 100644 --- a/src/AutoPilotPlugins/Common/MotorComponent.h +++ b/src/AutoPilotPlugins/Common/MotorComponent.h @@ -7,7 +7,6 @@ * ****************************************************************************/ - #pragma once #include "VehicleComponent.h" @@ -15,22 +14,19 @@ class MotorComponent : public VehicleComponent { Q_OBJECT - + public: - MotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr); - - // Virtuals from VehicleComponent - QStringList setupCompleteChangedTriggerList(void) const final; - - // Virtuals from VehicleComponent - QString name(void) const final; - QString description(void) const final; - QString iconResource(void) const final; - bool requiresSetup(void) const final; - bool setupComplete(void) const final; - virtual QUrl setupSource(void) const; - QUrl summaryQmlSource(void) const final; + explicit MotorComponent(Vehicle *vehicle, AutoPilotPlugin *autopilot, QObject *parent = nullptr); + + QStringList setupCompleteChangedTriggerList() const override { return QStringList(); } + QString name() const override { return _name; } + QString description() const override { return tr("Motors Setup is used to manually test motor control and direction."); } + QString iconResource() const override { return QStringLiteral("/qmlimages/MotorComponentIcon.svg"); } + bool requiresSetup() const override { return false; } + bool setupComplete() const override { return true; } + QUrl setupSource() const override { return QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/Controls/MotorComponent.qml")); } + QUrl summaryQmlSource() const override { return QUrl(); } private: - const QString _name; + const QString _name; }; diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.cc b/src/AutoPilotPlugins/Common/RadioComponentController.cc index 8f7591045f8..dbf6d7de3aa 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.cc +++ b/src/AutoPilotPlugins/Common/RadioComponentController.cc @@ -7,159 +7,168 @@ * ****************************************************************************/ - -/// @file -/// @brief Radio Config Qml Controller -/// @author Don Gagne -QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "RadioComponentControllerLog") -QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "RadioComponentControllerVerboseLog") +QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "qgc.autopilotplugins.common.radiocomponentcontroller") +QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "qgc.autopilotplugins.common.radiocomponentcontroller:verbose") #ifdef QGC_UNITTEST_BUILD -// Nasty hack to expose controller to unit test code RadioComponentController* RadioComponentController::_unitTestController = nullptr; #endif -RadioComponentController::RadioComponentController(void) - : _currentStep(-1) - , _transmitterMode(2) - , _chanCount(0) - , _rcCalState(rcCalStateChannelWait) +RadioComponentController::RadioComponentController(QObject *parent) + : FactPanelController(parent) { + // qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this; + #ifdef QGC_UNITTEST_BUILD - // Nasty hack to expose controller to unit test code _unitTestController = this; #endif if (parameterExists(ParameterManager::defaultComponentId, QStringLiteral("RC1_REVERSED"))) { // Newer ardupilot firmwares have a different reverse param naming scheme and value scheme - _revParamFormat = _apmNewRevParamFormat; + _revParamFormat = "RC%1_REVERSED"; _revParamIsBool = true; // param value is boolean 0/1 for reversed or not } else { // Older ardupilot firmwares share the same naming convention as PX4 - _revParamFormat = _px4RevParamFormat; - _revParamIsBool = false; // paeram value if -1 indicates reversed + _revParamFormat = "RC%1_REV"; + _revParamIsBool = false; // param value if -1 indicates reversed } - connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged); + (void) connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged); _loadSettings(); _resetInternalCalibrationValues(); } -void RadioComponentController::start(void) +RadioComponentController::~RadioComponentController() { - _stopCalibration(); - _setInternalCalibrationValuesFromParameters(); + _storeSettings(); + + // qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this; } -RadioComponentController::~RadioComponentController() +void RadioComponentController::start() { - _storeSettings(); + _stopCalibration(); + _setInternalCalibrationValuesFromParameters(); } -/// @brief Returns the state machine entry for the specified state. const RadioComponentController::stateMachineEntry* RadioComponentController::_getStateMachineEntry(int step) const { - static const char* msgBeginPX4 = QT_TR_NOOP("Lower the Throttle stick all the way down as shown in diagram.\n\n" - "It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n" - "Click Next to continue"); - static const char* msgBeginAPM = QT_TR_NOOP("Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n" - "Please ensure all motor power is disconnected AND all props are removed from the vehicle.\n\n" - "Click Next to continue"); - static const char* msgThrottleUp = QT_TR_NOOP("Move the Throttle stick all the way up and hold it there..."); - static const char* msgThrottleDown = QT_TR_NOOP("Move the Throttle stick all the way down and leave it there..."); - static const char* msgYawLeft = QT_TR_NOOP("Move the Yaw stick all the way to the left and hold it there..."); - static const char* msgYawRight = QT_TR_NOOP("Move the Yaw stick all the way to the right and hold it there..."); - static const char* msgRollLeft = QT_TR_NOOP("Move the Roll stick all the way to the left and hold it there..."); - static const char* msgRollRight = QT_TR_NOOP("Move the Roll stick all the way to the right and hold it there..."); - static const char* msgPitchDown = QT_TR_NOOP("Move the Pitch stick all the way down and hold it there..."); - static const char* msgPitchUp = QT_TR_NOOP("Move the Pitch stick all the way up and hold it there..."); - static const char* msgPitchCenter = QT_TR_NOOP("Allow the Pitch stick to move back to center..."); - static const char* msgSwitchMinMax = QT_TR_NOOP("Move all the transmitter switches and/or dials back and forth to their extreme positions."); - static const char* msgComplete = QT_TR_NOOP("All settings have been captured. Click Next to write the new parameters to your board."); - - static const stateMachineEntry rgStateMachinePX4[] = { + static constexpr const char *msgBeginPX4 = QT_TR_NOOP( + "Lower the Throttle stick all the way down as shown in diagram.\n\n" + "It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n" + "Click Next to continue" + ); + static constexpr const char *msgBeginAPM = QT_TR_NOOP( + "Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n" + "Please ensure all motor power is disconnected AND all props are removed from the vehicle.\n\n" + "Click Next to continue" + ); + static constexpr const char *msgThrottleUp = QT_TR_NOOP("Move the Throttle stick all the way up and hold it there..."); + static constexpr const char *msgThrottleDown = QT_TR_NOOP("Move the Throttle stick all the way down and leave it there..."); + static constexpr const char *msgYawLeft = QT_TR_NOOP("Move the Yaw stick all the way to the left and hold it there..."); + static constexpr const char *msgYawRight = QT_TR_NOOP("Move the Yaw stick all the way to the right and hold it there..."); + static constexpr const char *msgRollLeft = QT_TR_NOOP("Move the Roll stick all the way to the left and hold it there..."); + static constexpr const char *msgRollRight = QT_TR_NOOP("Move the Roll stick all the way to the right and hold it there..."); + static constexpr const char *msgPitchDown = QT_TR_NOOP("Move the Pitch stick all the way down and hold it there..."); + static constexpr const char *msgPitchUp = QT_TR_NOOP("Move the Pitch stick all the way up and hold it there..."); + static constexpr const char *msgPitchCenter = QT_TR_NOOP("Allow the Pitch stick to move back to center..."); + static constexpr const char *msgSwitchMinMax = QT_TR_NOOP("Move all the transmitter switches and/or dials back and forth to their extreme positions."); + static constexpr const char *msgComplete = QT_TR_NOOP("All settings have been captured. Click Next to write the new parameters to your board."); + + static constexpr const char *imageHome = "radioHome.png"; + static constexpr const char *imageThrottleUp = "radioThrottleUp.png"; + static constexpr const char *imageThrottleDown = "radioThrottleDown.png"; + static constexpr const char *imageYawLeft = "radioYawLeft.png"; + static constexpr const char *imageYawRight = "radioYawRight.png"; + static constexpr const char *imageRollLeft = "radioRollLeft.png"; + static constexpr const char *imageRollRight = "radioRollRight.png"; + static constexpr const char *imagePitchUp = "radioPitchUp.png"; + static constexpr const char *imagePitchDown = "radioPitchDown.png"; + static constexpr const char *imageSwitchMinMax = "radioSwitchMinMax.png"; + + static constexpr const stateMachineEntry rgStateMachinePX4[] = { //Function - { rcCalFunctionMax, msgBeginPX4, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, nullptr }, - { rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, nullptr, nullptr }, - { rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, nullptr }, - { rcCalFunctionMax, msgComplete, _imageThrottleDown, nullptr, &RadioComponentController::_writeCalibration, nullptr }, + { rcCalFunctionMax, msgBeginPX4, imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, nullptr }, + { rcCalFunctionThrottle, msgThrottleUp, imageThrottleUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionThrottle, msgThrottleDown, imageThrottleDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionYaw, msgYawRight, imageYawRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionYaw, msgYawLeft, imageYawLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionRoll, msgRollRight, imageRollRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionRoll, msgRollLeft, imageRollLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionPitch, msgPitchUp, imagePitchUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionPitch, msgPitchDown, imagePitchDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionPitch, msgPitchCenter, imageHome, &RadioComponentController::_inputCenterWait, nullptr, nullptr }, + { rcCalFunctionMax, msgSwitchMinMax, imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, nullptr }, + { rcCalFunctionMax, msgComplete, imageThrottleDown, nullptr, &RadioComponentController::_writeCalibration, nullptr }, }; - static const stateMachineEntry rgStateMachineAPM[] = { + static constexpr const stateMachineEntry rgStateMachineAPM[] = { //Function - { rcCalFunctionMax, msgBeginAPM, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, nullptr }, - { rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, - { rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, - { rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, nullptr, nullptr }, - { rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, nullptr }, - { rcCalFunctionMax, msgComplete, _imageThrottleDown, nullptr, &RadioComponentController::_writeCalibration, nullptr }, + { rcCalFunctionMax, msgBeginAPM, imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, nullptr }, + { rcCalFunctionThrottle, msgThrottleUp, imageThrottleUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionThrottle, msgThrottleDown, imageThrottleDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionYaw, msgYawRight, imageYawRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionYaw, msgYawLeft, imageYawLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionRoll, msgRollRight, imageRollRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionRoll, msgRollLeft, imageRollLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionPitch, msgPitchUp, imagePitchUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr }, + { rcCalFunctionPitch, msgPitchDown, imagePitchDown, &RadioComponentController::_inputStickMin, nullptr, nullptr }, + { rcCalFunctionPitch, msgPitchCenter, imageHome, &RadioComponentController::_inputCenterWait, nullptr, nullptr }, + { rcCalFunctionMax, msgSwitchMinMax, imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, nullptr }, + { rcCalFunctionMax, msgComplete, imageThrottleDown, nullptr, &RadioComponentController::_writeCalibration, nullptr }, }; bool badStep = false; if (step < 0) { badStep = true; } + if (_px4Vehicle()) { - if (step >= static_cast(sizeof(rgStateMachinePX4) / sizeof(rgStateMachinePX4[0]))) { + if (step >= std::size(rgStateMachinePX4)) { badStep = true; } } else { - if (step >= static_cast(sizeof(rgStateMachineAPM) / sizeof(rgStateMachineAPM[0]))) { + if (step >= std::size(rgStateMachineAPM)) { badStep = true; } } + if (badStep) { - qWarning() << "Bad step value" << step; + qCWarning(RadioComponentControllerLog) << "Bad step value" << step; step = 0; } - const stateMachineEntry* stateMachine = _px4Vehicle() ? rgStateMachinePX4 : rgStateMachineAPM; - + const stateMachineEntry *const stateMachine = _px4Vehicle() ? rgStateMachinePX4 : rgStateMachineAPM; return &stateMachine[step]; } -void RadioComponentController::_advanceState(void) +void RadioComponentController::_advanceState() { _currentStep++; _setupCurrentState(); } - -/// @brief Sets up the state machine according to the current step from _currentStep. -void RadioComponentController::_setupCurrentState(void) +void RadioComponentController::_setupCurrentState() { - static const char* msgBeginAPMRover = QT_TR_NOOP("Center the Throttle stick as shown in diagram.\nReset all transmitter trims to center.\n\n" - "Please ensure all motor power is disconnected from the vehicle.\n\n" - "Click Next to continue"); - const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - - const char* instructions = state->instructions; - const char* helpImage = state->image; + static constexpr const char *msgBeginAPMRover = QT_TR_NOOP( + "Center the Throttle stick as shown in diagram.\nReset all transmitter trims to center.\n\n" + "Please ensure all motor power is disconnected from the vehicle.\n\n" + "Click Next to continue" + ); + const stateMachineEntry *const state = _getStateMachineEntry(_currentStep); + + const char *instructions = state->instructions; + const char *helpImage = state->image; if (_vehicle->rover() && _currentStep == 0) { // Hack in center throttle start for Rover. This is to set the correct centered trim for throttle. instructions = msgBeginAPMRover; @@ -177,7 +186,6 @@ void RadioComponentController::_setupCurrentState(void) _skipButton->setEnabled(state->skipFn != nullptr); } -/// Connected to Vehicle::rcChannelsChanged signal void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValues[QGCMAVLink::maxRcChannels]) { // Below is a hack that's needed by ELRS @@ -191,7 +199,7 @@ void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValue } for (int channel=0; channelrcInputFn) { (this->*state->rcInputFn)(state->function, channel, channelValue); } } else { - qWarning() << "Internal error: nullptr _getStateMachineEntry return"; + qCWarning(RadioComponentControllerLog) << "Internal error: nullptr _getStateMachineEntry return"; } } } } } -void RadioComponentController::nextButtonClicked(void) +void RadioComponentController::nextButtonClicked() { if (_currentStep == -1) { // Need to have enough channels @@ -247,22 +254,22 @@ void RadioComponentController::nextButtonClicked(void) if (_unitTestMode) { emit nextButtonMessageBoxDisplayed(); } else { - qgcApp()->showAppMessage(QString("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); + qgcApp()->showAppMessage(QStringLiteral("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); } return; } _startCalibration(); } else { - const stateMachineEntry* state = _getStateMachineEntry(_currentStep); + const stateMachineEntry *const state = _getStateMachineEntry(_currentStep); if (state && state->nextFn) { (this->*state->nextFn)(); } else { - qWarning() << "Internal error: nullptr _getStateMachineEntry return"; + qCWarning(RadioComponentControllerLog) << "Internal error: nullptr _getStateMachineEntry return"; } } } -void RadioComponentController::skipButtonClicked(void) +void RadioComponentController::skipButtonClicked() { if (_currentStep == -1) { qWarning() << "Internal error: _currentStep == -1"; @@ -273,16 +280,16 @@ void RadioComponentController::skipButtonClicked(void) if (state && state->skipFn) { (this->*state->skipFn)(); } else { - qWarning() << "Internal error: nullptr _getStateMachineEntry return"; + qCWarning(RadioComponentControllerLog) << "Internal error: nullptr _getStateMachineEntry return"; } } -void RadioComponentController::cancelButtonClicked(void) +void RadioComponentController::cancelButtonClicked() { _stopCalibration(); } -void RadioComponentController::_saveAllTrims(void) +void RadioComponentController::_saveAllTrims() { // We save all trims as the first step. At this point no channels are mapped but it should still // allow us to get good trims for the roll/pitch/yaw/throttle even though we don't know which @@ -297,14 +304,13 @@ void RadioComponentController::_saveAllTrims(void) } /// @brief Waits for the sticks to be centered, enabling Next when done. -void RadioComponentController::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value) +void RadioComponentController::_inputCenterWaitBegin(rcCalFunctions function, int chan, int value) { Q_UNUSED(function); Q_UNUSED(chan); Q_UNUSED(value); // FIXME: Doesn't wait for center - _nextButton->setEnabled(true); } @@ -342,7 +348,7 @@ bool RadioComponentController::_stickSettleComplete(int value) return false; } -void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputStickDetect(rcCalFunctions function, int channel, int value) { // If this channel is already used in a mapping we can't use it again if (_rgChannelInfo[channel].function != rcCalFunctionMax) { @@ -365,7 +371,7 @@ void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, i } } else if (channel == _stickDetectChannel) { if (_stickSettleComplete(value)) { - ChannelInfo* info = &_rgChannelInfo[channel]; + ChannelInfo *const info = &_rgChannelInfo[channel]; // Map the channel to the function _rgFunctionChannelMapping[function] = channel; @@ -388,14 +394,14 @@ void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, i } } -void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputStickMin(rcCalFunctions function, int channel, int value) { // We only care about the channel mapped to the function we are working on if (_rgFunctionChannelMapping[function] != channel) { return; } - QString functionParamName = _functionInfo()[function].parameterName; + const QString functionParamName = _functionInfo()[function].parameterName; qCDebug(RadioComponentControllerLog) << "_inputStickMin function:channel:value" << functionParamName << channel << value; if (_stickDetectChannel == _chanMax) { @@ -416,7 +422,7 @@ void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int } else { // We are waiting for the selected channel to settle out if (_stickSettleComplete(value)) { - ChannelInfo* info = &_rgChannelInfo[channel]; + const ChannelInfo *const info = &_rgChannelInfo[channel]; // Stick detection is complete. Stick should be at extreme position. if (info->reversed) { @@ -439,14 +445,14 @@ void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int } } -void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputCenterWait(rcCalFunctions function, int channel, int value) { // We only care about the channel mapped to the function we are working on if (_rgFunctionChannelMapping[function] != channel) { return; } - QString functionParamName = _functionInfo()[function].parameterName; + const QString functionParamName = _functionInfo()[function].parameterName; qCDebug(RadioComponentControllerLog) << "_inputCenterWait function:channel:value" << functionParamName << channel << value; if (_stickDetectChannel == _chanMax) { @@ -465,8 +471,7 @@ void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, in } } -/// @brief Saves min/max for non-mapped channels -void RadioComponentController::_inputSwitchMinMax(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputSwitchMinMax(rcCalFunctions function, int channel, int value) { Q_UNUSED(function); @@ -478,22 +483,22 @@ void RadioComponentController::_inputSwitchMinMax(enum rcCalFunctions function, if (abs(_rcCalPWMCenterPoint - value) > _rcCalMoveDelta) { // Stick has moved far enough from center to consider for min/max if (value < _rcCalPWMCenterPoint) { - int minValue = qMin(_rgChannelInfo[channel].rcMin, value); + const int minValue = qMin(_rgChannelInfo[channel].rcMin, value); - qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting min channel:min" << channel << minValue; + qCDebug(RadioComponentControllerLog) << "setting min channel:min" << channel << minValue; _rgChannelInfo[channel].rcMin = minValue; } else { int maxValue = qMax(_rgChannelInfo[channel].rcMax, value); - qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue; + qCDebug(RadioComponentControllerLog) << "setting max channel:max" << channel << maxValue; _rgChannelInfo[channel].rcMax = maxValue; } } } -void RadioComponentController::_switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep) +void RadioComponentController::_switchDetect(rcCalFunctions function, int channel, int value, bool moveToNextStep) { // If this channel is already used in a mapping we can't use it again if (_rgChannelInfo[channel].function != rcCalFunctionMax) { @@ -501,7 +506,7 @@ void RadioComponentController::_switchDetect(enum rcCalFunctions function, int c } if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) { - ChannelInfo* info = &_rgChannelInfo[channel]; + ChannelInfo *const info = &_rgChannelInfo[channel]; // Switch has moved far enough to consider it as being selected for the function @@ -518,17 +523,16 @@ void RadioComponentController::_switchDetect(enum rcCalFunctions function, int c } } -void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputSwitchDetect(rcCalFunctions function, int channel, int value) { _switchDetect(function, channel, value, true /* move to next step after detection */); } -/// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence. -void RadioComponentController::_resetInternalCalibrationValues(void) +void RadioComponentController::_resetInternalCalibrationValues() { // Set all raw channels to not reversed and center point values - for (int i=0; i<_chanMax; i++) { - struct ChannelInfo* info = &_rgChannelInfo[i]; + for (int i = 0; i < _chanMax; i++) { + ChannelInfo *const info = &_rgChannelInfo[i]; info->function = rcCalFunctionMax; info->reversed = false; info->rcMin = RadioComponentController::_rcCalPWMCenterPoint; @@ -537,35 +541,34 @@ void RadioComponentController::_resetInternalCalibrationValues(void) } // Initialize attitude function mapping to function channel not set - for (size_t i=0; ifunction = rcCalFunctionMax; } - for (size_t i=0; ircTrim = 1500; @@ -575,7 +578,7 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) continue; } - Fact* paramFact = getParameterFact(ParameterManager::defaultComponentId, trimTpl.arg(i+1)); + Fact *paramFact = getParameterFact(ParameterManager::defaultComponentId, trimTpl.arg(i+1)); if (paramFact) { info->rcTrim = paramFact->rawValue().toInt(); } @@ -596,9 +599,9 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) for (int i=0; irawValue().toInt(); @@ -623,11 +626,10 @@ void RadioComponentController::crsfBindMode() _vehicle->pairRX(RC_TYPE_CRSF, 0); } -/// @brief Validates the current settings against the calibration rules resetting values as necessary. -void RadioComponentController::_validateCalibration(void) +void RadioComponentController::_validateCalibration() { for (int chan = 0; chan<_chanMax; chan++) { - struct ChannelInfo* info = &_rgChannelInfo[chan]; + ChannelInfo *info = &_rgChannelInfo[chan]; if (chan < _chanCount) { // Validate Min/Max values. Although the channel appears as available we still may @@ -668,27 +670,25 @@ void RadioComponentController::_validateCalibration(void) } } - -/// @brief Saves the rc calibration values to the board parameters. -void RadioComponentController::_writeCalibration(void) +void RadioComponentController::_writeCalibration() { if (!_vehicle) return; - if (!_px4Vehicle() && (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER || _vehicle->multiRotor()) && _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed) { + if (!_px4Vehicle() && ((_vehicle->vehicleType() == MAV_TYPE_HELICOPTER) || (_vehicle->multiRotor()) && _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed)) { // A reversed throttle could lead to dangerous power up issues if the firmware doesn't handle it absolutely correctly in all places. // So in this case fail the calibration for anything other than PX4 which is known to be able to handle this correctly. emit throttleReversedCalFailure(); } else { _validateCalibration(); - QString minTpl("RC%1_MIN"); - QString maxTpl("RC%1_MAX"); - QString trimTpl("RC%1_TRIM"); + const QString minTpl("RC%1_MIN"); + const QString maxTpl("RC%1_MAX"); + const QString trimTpl("RC%1_TRIM"); // Note that the rc parameters are all float, so you must cast to float in order to get the right QVariant for (int chan = 0; chan<_chanMax; chan++) { - struct ChannelInfo* info = &_rgChannelInfo[chan]; - int oneBasedChannel = chan + 1; + ChannelInfo *const info = &_rgChannelInfo[chan]; + const int oneBasedChannel = chan + 1; if (!parameterExists(ParameterManager::defaultComponentId, minTpl.arg(chan+1))) { continue; @@ -731,7 +731,8 @@ void RadioComponentController::_writeCalibration(void) // Note that the channel value is 1-based paramChannel = _rgFunctionChannelMapping[i] + 1; } - const char* paramName = _functionInfo()[i].parameterName; + + const char *const paramName = _functionInfo()[i].parameterName; if (paramName) { Fact* paramFact = getParameterFact(ParameterManager::defaultComponentId, _functionInfo()[i].parameterName); @@ -756,11 +757,10 @@ void RadioComponentController::_writeCalibration(void) _setInternalCalibrationValuesFromParameters(); } -/// @brief Starts the calibration process -void RadioComponentController::_startCalibration(void) +void RadioComponentController::_startCalibration() { if (_chanCount < _chanMinimum) { - qWarning() << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum"; + qCWarning(RadioComponentControllerLog) << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum"; return; } @@ -776,8 +776,7 @@ void RadioComponentController::_startCalibration(void) _setupCurrentState(); } -/// @brief Cancels the calibration process, setting things back to initial state. -void RadioComponentController::_stopCalibration(void) +void RadioComponentController::_stopCalibration() { _currentStep = -1; @@ -790,17 +789,26 @@ void RadioComponentController::_stopCalibration(void) _resetInternalCalibrationValues(); } - if(_statusText) _statusText->setProperty("text", ""); - if(_nextButton) _nextButton->setProperty("text", tr("Calibrate")); - if(_nextButton) _nextButton->setEnabled(true); - if(_cancelButton) _cancelButton->setEnabled(false); - if(_skipButton) _skipButton->setEnabled(false); + if (_statusText) { + _statusText->setProperty("text", ""); + } + if (_nextButton) { + _nextButton->setProperty("text", tr("Calibrate")); + } + if (_nextButton) { + _nextButton->setEnabled(true); + } + if (_cancelButton) { + _cancelButton->setEnabled(false); + } + if (_skipButton) { + _skipButton->setEnabled(false); + } _setHelpImage(_imageCenter); } -/// @brief Saves the current channel values, so that we can detect when the use moves an input. -void RadioComponentController::_rcCalSaveCurrentValues(void) +void RadioComponentController::_rcCalSaveCurrentValues() { for (int i = 0; i < _chanMax; i++) { _rcValueSave[i] = _rcRawValue[i]; @@ -808,26 +816,34 @@ void RadioComponentController::_rcCalSaveCurrentValues(void) } } -/// @brief Set up the Save state of calibration. -void RadioComponentController::_rcCalSave(void) +void RadioComponentController::_rcCalSave() { _rcCalState = rcCalStateSave; - if(_statusText) _statusText->setProperty( - "text", - tr("The current calibration settings are now displayed for each channel on screen.\n\n" - "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values.")); + if (_statusText) { + _statusText->setProperty( + "text", + tr("The current calibration settings are now displayed for each channel on screen.\n\n" + "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values.") + ); + } - if(_nextButton) _nextButton->setEnabled(true); - if(_skipButton) _skipButton->setEnabled(false); - if(_cancelButton) _cancelButton->setEnabled(true); + if (_nextButton) { + _nextButton->setEnabled(true); + } + if (_skipButton) { + _skipButton->setEnabled(false); + } + if (_cancelButton) { + _cancelButton->setEnabled(true); + } // This updates the internal values according to the validation rules. Then _updateView will tick and update ui // such that the settings that will be written our are displayed. _validateCalibration(); } -void RadioComponentController::_loadSettings(void) +void RadioComponentController::_loadSettings() { QSettings settings; @@ -840,7 +856,7 @@ void RadioComponentController::_loadSettings(void) } } -void RadioComponentController::_storeSettings(void) +void RadioComponentController::_storeSettings() { QSettings settings; @@ -849,16 +865,20 @@ void RadioComponentController::_storeSettings(void) settings.endGroup(); } -void RadioComponentController::_setHelpImage(const char* imageFile) +void RadioComponentController::_setHelpImage(const char *imageFile) { - QString file = _imageFilePrefix; + static constexpr const char *imageFilePrefix = "calibration/"; + static constexpr const char *imageFileMode1Dir = "mode1/"; + static constexpr const char *imageFileMode2Dir = "mode2/"; + + QString file = imageFilePrefix; if (_transmitterMode == 1) { - file += _imageFileMode1Dir; + file += imageFileMode1Dir; } else if (_transmitterMode == 2) { - file += _imageFileMode2Dir; + file += imageFileMode2Dir; } else { - qWarning() << "Internal error: Bad _transmitterMode value"; + qCWarning(RadioComponentControllerLog) << "Internal error: Bad _transmitterMode value"; return; } file += imageFile; @@ -869,12 +889,7 @@ void RadioComponentController::_setHelpImage(const char* imageFile) emit imageHelpChanged(file); } -int RadioComponentController::channelCount(void) const -{ - return _chanCount; -} - -int RadioComponentController::rollChannelRCValue(void) +int RadioComponentController::rollChannelRCValue() { if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) { return _rcRawValue[rcCalFunctionRoll]; @@ -883,7 +898,7 @@ int RadioComponentController::rollChannelRCValue(void) } } -int RadioComponentController::pitchChannelRCValue(void) +int RadioComponentController::pitchChannelRCValue() { if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax) { return _rcRawValue[rcCalFunctionPitch]; @@ -892,7 +907,7 @@ int RadioComponentController::pitchChannelRCValue(void) } } -int RadioComponentController::yawChannelRCValue(void) +int RadioComponentController::yawChannelRCValue() { if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax) { return _rcRawValue[rcCalFunctionYaw]; @@ -901,7 +916,7 @@ int RadioComponentController::yawChannelRCValue(void) } } -int RadioComponentController::throttleChannelRCValue(void) +int RadioComponentController::throttleChannelRCValue() { if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) { return _rcRawValue[rcCalFunctionThrottle]; @@ -910,27 +925,27 @@ int RadioComponentController::throttleChannelRCValue(void) } } -bool RadioComponentController::rollChannelMapped(void) +bool RadioComponentController::rollChannelMapped() { - return _rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax; + return (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax); } -bool RadioComponentController::pitchChannelMapped(void) +bool RadioComponentController::pitchChannelMapped() { - return _rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax; + return (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax); } -bool RadioComponentController::yawChannelMapped(void) +bool RadioComponentController::yawChannelMapped() { - return _rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax; + return (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax); } -bool RadioComponentController::throttleChannelMapped(void) +bool RadioComponentController::throttleChannelMapped() { - return _rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax; + return (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax); } -bool RadioComponentController::rollChannelReversed(void) +bool RadioComponentController::rollChannelReversed() { if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) { return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionRoll]].reversed; @@ -939,7 +954,7 @@ bool RadioComponentController::rollChannelReversed(void) } } -bool RadioComponentController::pitchChannelReversed(void) +bool RadioComponentController::pitchChannelReversed() { if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax) { return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionPitch]].reversed; @@ -948,7 +963,7 @@ bool RadioComponentController::pitchChannelReversed(void) } } -bool RadioComponentController::yawChannelReversed(void) +bool RadioComponentController::yawChannelReversed() { if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax) { return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionYaw]].reversed; @@ -957,7 +972,7 @@ bool RadioComponentController::yawChannelReversed(void) } } -bool RadioComponentController::throttleChannelReversed(void) +bool RadioComponentController::throttleChannelReversed() { if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) { return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed; @@ -977,7 +992,7 @@ void RadioComponentController::setTransmitterMode(int mode) } } -void RadioComponentController::_signalAllAttitudeValueChanges(void) +void RadioComponentController::_signalAllAttitudeValueChanges() { emit rollChannelMappedChanged(rollChannelMapped()); emit pitchChannelMappedChanged(pitchChannelMapped()); @@ -990,24 +1005,38 @@ void RadioComponentController::_signalAllAttitudeValueChanges(void) emit throttleChannelReversedChanged(throttleChannelReversed()); } -void RadioComponentController::copyTrims(void) +void RadioComponentController::copyTrims() { _vehicle->startCalibration(QGCMAVLink::CalibrationCopyTrims); } -bool RadioComponentController::_px4Vehicle(void) const +bool RadioComponentController::_px4Vehicle() const { - return _vehicle->firmwareType() == MAV_AUTOPILOT_PX4; + return (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4); } -const struct RadioComponentController::FunctionInfo* RadioComponentController::_functionInfo(void) const +const struct RadioComponentController::FunctionInfo *RadioComponentController::_functionInfo(void) const { - return _px4Vehicle() ? _rgFunctionInfoPX4 : _rgFunctionInfoAPM; + static constexpr const struct FunctionInfo rgFunctionInfoPX4[rcCalFunctionMax] = { + { "RC_MAP_ROLL" }, + { "RC_MAP_PITCH" }, + { "RC_MAP_YAW" }, + { "RC_MAP_THROTTLE" } + }; + + static constexpr const struct FunctionInfo rgFunctionInfoAPM[rcCalFunctionMax] = { + { "RCMAP_ROLL" }, + { "RCMAP_PITCH" }, + { "RCMAP_YAW" }, + { "RCMAP_THROTTLE" } + }; + + return (_px4Vehicle() ? rgFunctionInfoPX4 : rgFunctionInfoAPM); } bool RadioComponentController::_channelReversedParamValue(int channel) { - Fact* paramFact = getParameterFact(ParameterManager::defaultComponentId, _revParamFormat.arg(channel+1)); + Fact *const paramFact = getParameterFact(ParameterManager::defaultComponentId, _revParamFormat.arg(channel+1)); if (paramFact) { if (_revParamIsBool) { return paramFact->rawValue().toBool(); @@ -1017,6 +1046,7 @@ bool RadioComponentController::_channelReversedParamValue(int channel) if (!convertOk) { floatReversed = 1.0f; } + return floatReversed == -1.0f; } } @@ -1026,7 +1056,7 @@ bool RadioComponentController::_channelReversedParamValue(int channel) void RadioComponentController::_setChannelReversedParamValue(int channel, bool reversed) { - Fact* paramFact = getParameterFact(ParameterManager::defaultComponentId, _revParamFormat.arg(channel+1)); + Fact *const paramFact = getParameterFact(ParameterManager::defaultComponentId, _revParamFormat.arg(channel+1)); if (paramFact) { if (_revParamIsBool) { paramFact->setRawValue(reversed); diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.h b/src/AutoPilotPlugins/Common/RadioComponentController.h index 0e03f3017cd..760765f6371 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.h +++ b/src/AutoPilotPlugins/Common/RadioComponentController.h @@ -7,67 +7,48 @@ * ****************************************************************************/ - - -/// @file -/// @brief Radio Config Qml Controller -/// @author Don Gagne #include #include +#include "FactPanelController.h" +#include "QGCMAVLink.h" + Q_DECLARE_LOGGING_CATEGORY(RadioComponentControllerLog) Q_DECLARE_LOGGING_CATEGORY(RadioComponentControllerVerboseLog) -class RadioConfigest; - -namespace Ui { - class RadioComponentController; -} - - class RadioComponentController : public FactPanelController { Q_OBJECT - - //friend class RadioConfigTest; ///< This allows our unit test to access internal information needed. - -public: - RadioComponentController(void); - ~RadioComponentController(); - Q_PROPERTY(int minChannelCount MEMBER _chanMinimum CONSTANT) Q_PROPERTY(int channelCount READ channelCount NOTIFY channelCountChanged) - - Q_PROPERTY(QQuickItem* statusText MEMBER _statusText NOTIFY statusTextChanged) - Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton NOTIFY cancelButtonChanged) - Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton NOTIFY nextButtonChanged) - Q_PROPERTY(QQuickItem* skipButton MEMBER _skipButton NOTIFY skipButtonChanged) - + Q_PROPERTY(QQuickItem *statusText MEMBER _statusText NOTIFY statusTextChanged) + Q_PROPERTY(QQuickItem *cancelButton MEMBER _cancelButton NOTIFY cancelButtonChanged) + Q_PROPERTY(QQuickItem *nextButton MEMBER _nextButton NOTIFY nextButtonChanged) + Q_PROPERTY(QQuickItem *skipButton MEMBER _skipButton NOTIFY skipButtonChanged) Q_PROPERTY(bool rollChannelMapped READ rollChannelMapped NOTIFY rollChannelMappedChanged) Q_PROPERTY(bool pitchChannelMapped READ pitchChannelMapped NOTIFY pitchChannelMappedChanged) Q_PROPERTY(bool yawChannelMapped READ yawChannelMapped NOTIFY yawChannelMappedChanged) Q_PROPERTY(bool throttleChannelMapped READ throttleChannelMapped NOTIFY throttleChannelMappedChanged) - Q_PROPERTY(int rollChannelRCValue READ rollChannelRCValue NOTIFY rollChannelRCValueChanged) Q_PROPERTY(int pitchChannelRCValue READ pitchChannelRCValue NOTIFY pitchChannelRCValueChanged) Q_PROPERTY(int yawChannelRCValue READ yawChannelRCValue NOTIFY yawChannelRCValueChanged) Q_PROPERTY(int throttleChannelRCValue READ throttleChannelRCValue NOTIFY throttleChannelRCValueChanged) - Q_PROPERTY(int rollChannelReversed READ rollChannelReversed NOTIFY rollChannelReversedChanged) Q_PROPERTY(int pitchChannelReversed READ pitchChannelReversed NOTIFY pitchChannelReversedChanged) Q_PROPERTY(int yawChannelReversed READ yawChannelReversed NOTIFY yawChannelReversedChanged) Q_PROPERTY(int throttleChannelReversed READ throttleChannelReversed NOTIFY throttleChannelReversedChanged) - Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged) Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged) + friend class RadioConfigTest; + +public: + RadioComponentController(QObject *parent = nullptr); + ~RadioComponentController(); + enum BindModes { DSM2, DSMX7, @@ -76,38 +57,38 @@ class RadioComponentController : public FactPanelController Q_ENUM(BindModes) Q_INVOKABLE void spektrumBindMode(int mode); - Q_INVOKABLE void crsfBindMode(void); - Q_INVOKABLE void cancelButtonClicked(void); - Q_INVOKABLE void skipButtonClicked(void); - Q_INVOKABLE void nextButtonClicked(void); - Q_INVOKABLE void start(void); - Q_INVOKABLE void copyTrims(void); - - int rollChannelRCValue(void); - int pitchChannelRCValue(void); - int yawChannelRCValue(void); - int throttleChannelRCValue(void); - - bool rollChannelMapped(void); - bool pitchChannelMapped(void); - bool yawChannelMapped(void); - bool throttleChannelMapped(void); - - bool rollChannelReversed(void); - bool pitchChannelReversed(void); - bool yawChannelReversed(void); - bool throttleChannelReversed(void); - - int channelCount(void) const; - - int transmitterMode(void) const{ return _transmitterMode; } + Q_INVOKABLE void crsfBindMode(); + Q_INVOKABLE void cancelButtonClicked(); + Q_INVOKABLE void skipButtonClicked(); + Q_INVOKABLE void nextButtonClicked(); + Q_INVOKABLE void start(); + Q_INVOKABLE void copyTrims(); + + int rollChannelRCValue(); + int pitchChannelRCValue(); + int yawChannelRCValue(); + int throttleChannelRCValue(); + + bool rollChannelMapped(); + bool pitchChannelMapped(); + bool yawChannelMapped(); + bool throttleChannelMapped(); + + bool rollChannelReversed(); + bool pitchChannelReversed(); + bool yawChannelReversed(); + bool throttleChannelReversed(); + + int channelCount() const { return _chanCount; } + + int transmitterMode() const { return _transmitterMode; } void setTransmitterMode(int mode); signals: - void statusTextChanged(void); - void cancelButtonChanged(void); - void nextButtonChanged(void); - void skipButtonChanged(void); + void statusTextChanged(); + void cancelButtonChanged(); + void nextButtonChanged(); + void skipButtonChanged(); void channelCountChanged(int channelCount); void channelRCValueChanged(int channel, int rcValue); @@ -131,20 +112,20 @@ class RadioComponentController : public FactPanelController void transmitterModeChanged(int mode); /// Signalled when in unit test mode and a message box should be displayed by the next button - void nextButtonMessageBoxDisplayed(void); + void nextButtonMessageBoxDisplayed(); /// Signalled to QML to indicate reboot is required - void functionMappingChangedAPMReboot(void); + void functionMappingChangedAPMReboot(); /// Signalled to Qml to indicate cal failure due to reversed throttle - void throttleReversedCalFailure(void); + void throttleReversedCalFailure(); private slots: + /// Connected to Vehicle::rcChannelsChanged signal void _rcChannelsChanged(int channelCount, int pwmValues[QGCMAVLink::maxRcChannels]); private: - /// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo - /// array. + /// These identify the various controls functions. They are also used as indices into the _rgFunctioInfo array. enum rcCalFunctions { rcCalFunctionRoll, rcCalFunctionPitch, @@ -153,182 +134,152 @@ private slots: rcCalFunctionMax, }; - /// @brief The states of the calibration state machine. - enum rcCalStates { - rcCalStateChannelWait, - rcCalStateBegin, - rcCalStateIdentify, - rcCalStateMinMax, - rcCalStateCenterThrottle, - rcCalStateDetectInversion, - rcCalStateTrims, - rcCalStateSave - }; - typedef void (RadioComponentController::*inputFn)(enum rcCalFunctions function, int chan, int value); typedef void (RadioComponentController::*buttonFn)(void); struct stateMachineEntry { enum rcCalFunctions function; - const char* instructions; - const char* image; - inputFn rcInputFn; - buttonFn nextFn; - buttonFn skipFn; + const char *instructions; + const char *image; + inputFn rcInputFn; + buttonFn nextFn; + buttonFn skipFn; }; + /// Returns the state machine entry for the specified state. + const stateMachineEntry *_getStateMachineEntry(int step) const; - /// @brief A set of information associated with a function. + /// A set of information associated with a function. struct FunctionInfo { - const char* parameterName; ///< Parameter name for function mapping + const char *parameterName; ///< Parameter name for function mapping }; + const FunctionInfo *_functionInfo() const; - /// @brief A set of information associated with a radio channel. - struct ChannelInfo { - enum rcCalFunctions function; ///< Function mapped to this channel, rcCalFunctionMax for none - bool reversed; ///< true: channel is reverse, false: not reversed - int rcMin; ///< Minimum RC value - int rcMax; ///< Maximum RC value - int rcTrim; ///< Trim position - }; - - int _currentStep; ///< Current step of state machine - - const struct stateMachineEntry* _getStateMachineEntry(int step) const; - const struct FunctionInfo* _functionInfo(void) const; - bool _px4Vehicle(void) const; + bool _px4Vehicle() const; - void _advanceState(void); - void _setupCurrentState(void); + void _advanceState(); + /// Sets up the state machine according to the current step from _currentStep. + void _setupCurrentState(); - void _inputCenterWaitBegin(enum rcCalFunctions function, int channel, int value); - void _inputStickDetect(enum rcCalFunctions function, int channel, int value); - void _inputStickMin(enum rcCalFunctions function, int channel, int value); - void _inputCenterWait(enum rcCalFunctions function, int channel, int value); - void _inputSwitchMinMax(enum rcCalFunctions function, int channel, int value); - void _inputSwitchDetect(enum rcCalFunctions function, int channel, int value); + void _inputCenterWaitBegin(rcCalFunctions function, int channel, int value); + void _inputStickDetect(rcCalFunctions function, int channel, int value); + void _inputStickMin(rcCalFunctions function, int channel, int value); + void _inputCenterWait(rcCalFunctions function, int channel, int value); + /// Saves min/max for non-mapped channels + void _inputSwitchMinMax(rcCalFunctions function, int channel, int value); + void _inputSwitchDetect(rcCalFunctions function, int channel, int value); - void _switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep); + void _switchDetect(rcCalFunctions function, int channel, int value, bool moveToNextStep); - void _saveAllTrims(void); + void _saveAllTrims(); bool _stickSettleComplete(int value); - void _validateCalibration(void); - void _writeCalibration(void); - void _resetInternalCalibrationValues(void); - void _setInternalCalibrationValuesFromParameters(void); + /// Validates the current settings against the calibration rules resetting values as necessary. + void _validateCalibration(); + /// Saves the rc calibration values to the board parameters. + void _writeCalibration(); + /// Resets internal calibration values to their initial state in preparation for a new calibration sequence. + void _resetInternalCalibrationValues(); + /// Sets internal calibration values from the stored parameters + void _setInternalCalibrationValuesFromParameters(); - void _startCalibration(void); - void _stopCalibration(void); - void _rcCalSave(void); + /// Starts the calibration process + void _startCalibration(); + /// Cancels the calibration process, setting things back to initial state. + void _stopCalibration(); + /// Set up the Save state of calibration. + void _rcCalSave(); - void _writeParameters(void); + void _writeParameters(); - void _rcCalSaveCurrentValues(void); + /// Saves the current channel values, so that we can detect when the use moves an input. + void _rcCalSaveCurrentValues(); - void _setHelpImage(const char* imageFile); + void _setHelpImage(const char *imageFile); - void _loadSettings(void); - void _storeSettings(void); + void _loadSettings(); + void _storeSettings(); - void _signalAllAttitudeValueChanges(void); + void _signalAllAttitudeValueChanges(); bool _channelReversedParamValue(int channel); void _setChannelReversedParamValue(int channel, bool reversed); - // @brief Called by unit test code to set the mode to unit testing - void _setUnitTestMode(void){ _unitTestMode = true; } - - // Member variables - - int _transmitterMode; ///< 1: transmitter is mode 1, 2: transmitted is mode 2 - - int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function. + /// Called by unit test code to set the mode to unit testing + void _setUnitTestMode() { _unitTestMode = true; } - static const int _attitudeControls = 5; + int _currentStep = -1; ///< Current step of state machine + int _transmitterMode = 2; ///< 1: transmitter is mode 1, 2: transmitted is mode 2 + int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function. - int _chanCount; ///< Number of actual rc channels available - static const int _chanMax = 18; ///< Maximum number of support rc channels by this implementation - static const int _chanMinimum = 5; ///< Minimum numner of channels required to run + static constexpr int _attitudeControls = 5; - struct ChannelInfo _rgChannelInfo[_chanMax]; ///< Information associated with each rc channel + int _chanCount = 0; ///< Number of actual rc channels available + static constexpr int _chanMax = 18; ///< Maximum number of support rc channels by this implementation + static constexpr int _chanMinimum = 5; ///< Minimum numner of channels required to run - enum rcCalStates _rcCalState; ///< Current calibration state - int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion - bool _rcCalStateChannelComplete; ///< Work associated with current channel is complete - int _rcCalStateIdentifyOldMapping; ///< Previous mapping for channel being currently identified - int _rcCalStateReverseOldMapping; ///< Previous mapping for channel being currently used to detect inversion + /// A set of information associated with a radio channel. + struct ChannelInfo { + enum rcCalFunctions function; ///< Function mapped to this channel, rcCalFunctionMax for none + bool reversed; ///< true: channel is reverse, false: not reversed + int rcMin; ///< Minimum RC value + int rcMax; ///< Maximum RC value + int rcTrim; ///< Trim position + }; + ChannelInfo _rgChannelInfo[_chanMax]; ///< Information associated with each rc channel - QString _revParamFormat; - bool _revParamIsBool; + /// The states of the calibration state machine. + enum rcCalStates { + rcCalStateChannelWait, + rcCalStateBegin, + rcCalStateIdentify, + rcCalStateMinMax, + rcCalStateCenterThrottle, + rcCalStateDetectInversion, + rcCalStateTrims, + rcCalStateSave + }; + rcCalStates _rcCalState = rcCalStateChannelWait; ///< Current calibration state - int _rcValueSave[_chanMax]; ///< Saved values prior to detecting channel movement + QString _revParamFormat; + bool _revParamIsBool = false; - int _rcRawValue[_chanMax]; ///< Current set of raw channel values + int _rcValueSave[_chanMax]{}; ///< Saved values prior to detecting channel movement + int _rcRawValue[_chanMax]{}; ///< Current set of raw channel values - int _stickDetectChannel; - int _stickDetectValue; - bool _stickDetectSettleStarted; - QElapsedTimer _stickDetectSettleElapsed; + int _stickDetectChannel = 0; + int _stickDetectValue = 0; + bool _stickDetectSettleStarted = false; + QElapsedTimer _stickDetectSettleElapsed; - bool _unitTestMode = false; + bool _unitTestMode = false; - QQuickItem* _statusText = nullptr; - QQuickItem* _cancelButton = nullptr; - QQuickItem* _nextButton = nullptr; - QQuickItem* _skipButton = nullptr; + QQuickItem *_statusText = nullptr; + QQuickItem *_cancelButton = nullptr; + QQuickItem *_nextButton = nullptr; + QQuickItem *_skipButton = nullptr; QString _imageHelp; #ifdef QGC_UNITTEST_BUILD // Nasty hack to expose controller to unit test code - static RadioComponentController* _unitTestController; + static RadioComponentController *_unitTestController; #endif - static constexpr int _updateInterval = 150; ///< Interval for timer which updates radio channel widgets - static constexpr int _rcCalPWMValidMinValue = 1300; ///< Largest valid minimum PWM Min range value - static constexpr int _rcCalPWMValidMaxValue = 1700; ///< Smallest valid maximum PWM Max range value + static constexpr int _updateInterval = 150; ///< Interval for timer which updates radio channel widgets + static constexpr int _rcCalPWMValidMinValue = 1300; ///< Largest valid minimum PWM Min range value + static constexpr int _rcCalPWMValidMaxValue = 1700; ///< Smallest valid maximum PWM Max range value static constexpr int _rcCalPWMCenterPoint = ((_rcCalPWMValidMaxValue - _rcCalPWMValidMinValue) / 2.0f) + _rcCalPWMValidMinValue; - static constexpr int _rcCalPWMDefaultMinValue = 1000; ///< Default value for Min if not set - static constexpr int _rcCalPWMDefaultMaxValue = 2000; ///< Default value for Max if not set - static constexpr int _rcCalRoughCenterDelta = 50; ///< Delta around center point which is considered to be roughly centered - static constexpr int _rcCalMoveDelta = 300; ///< Amount of delta past center which is considered stick movement - static constexpr int _rcCalSettleDelta = 20; ///< Amount of delta which is considered no stick movement - static constexpr int _rcCalMinDelta = 100; ///< Amount of delta allowed around min value to consider channel at min + static constexpr int _rcCalPWMDefaultMinValue = 1000; ///< Default value for Min if not set + static constexpr int _rcCalPWMDefaultMaxValue = 2000; ///< Default value for Max if not set + static constexpr int _rcCalRoughCenterDelta = 50; ///< Delta around center point which is considered to be roughly centered + static constexpr int _rcCalMoveDelta = 300; ///< Amount of delta past center which is considered stick movement + static constexpr int _rcCalSettleDelta = 20; ///< Amount of delta which is considered no stick movement + static constexpr int _rcCalMinDelta = 100; ///< Amount of delta allowed around min value to consider channel at min static constexpr int _stickDetectSettleMSecs = 500; - static constexpr const char* _imageFilePrefix = "calibration/"; - static constexpr const char* _imageFileMode1Dir = "mode1/"; - static constexpr const char* _imageFileMode2Dir = "mode2/"; - static constexpr const char* _imageCenter = "radioCenter.png"; - static constexpr const char* _imageHome = "radioHome.png"; - static constexpr const char* _imageThrottleUp = "radioThrottleUp.png"; - static constexpr const char* _imageThrottleDown = "radioThrottleDown.png"; - static constexpr const char* _imageYawLeft = "radioYawLeft.png"; - static constexpr const char* _imageYawRight = "radioYawRight.png"; - static constexpr const char* _imageRollLeft = "radioRollLeft.png"; - static constexpr const char* _imageRollRight = "radioRollRight.png"; - static constexpr const char* _imagePitchUp = "radioPitchUp.png"; - static constexpr const char* _imagePitchDown = "radioPitchDown.png"; - static constexpr const char* _imageSwitchMinMax = "radioSwitchMinMax.png"; - - static constexpr const char* _settingsGroup = "RadioCalibration"; - static constexpr const char* _settingsKeyTransmitterMode = "TransmitterMode"; - - static constexpr const char* _px4RevParamFormat = "RC%1_REV"; - static constexpr const char* _apmNewRevParamFormat = "RC%1_REVERSED"; - - static constexpr const struct FunctionInfo _rgFunctionInfoPX4[rcCalFunctionMax] = { - { "RC_MAP_ROLL" }, - { "RC_MAP_PITCH" }, - { "RC_MAP_YAW" }, - { "RC_MAP_THROTTLE" } - }; + static constexpr const char *_settingsGroup = "RadioCalibration"; + static constexpr const char *_settingsKeyTransmitterMode = "TransmitterMode"; - static constexpr const struct FunctionInfo _rgFunctionInfoAPM[rcCalFunctionMax] = { - { "RCMAP_ROLL" }, - { "RCMAP_PITCH" }, - { "RCMAP_YAW" }, - { "RCMAP_THROTTLE" } - }; + static constexpr const char *_imageCenter = "radioCenter.png"; }; diff --git a/src/AutoPilotPlugins/Common/SyslinkComponent.cc b/src/AutoPilotPlugins/Common/SyslinkComponent.cc index b3ca1faec8f..fa87bd42de0 100644 --- a/src/AutoPilotPlugins/Common/SyslinkComponent.cc +++ b/src/AutoPilotPlugins/Common/SyslinkComponent.cc @@ -7,58 +7,11 @@ * ****************************************************************************/ - #include "SyslinkComponent.h" -#include "AutoPilotPlugin.h" -SyslinkComponent::SyslinkComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) +SyslinkComponent::SyslinkComponent(Vehicle *vehicle, AutoPilotPlugin *autopilot, QObject *parent) : VehicleComponent(vehicle, autopilot, AutoPilotPlugin::UnknownVehicleComponent, parent) , _name(tr("Syslink")) { } - -QString SyslinkComponent::name(void) const -{ - return _name; -} - -QString SyslinkComponent::description(void) const -{ - return tr("The Syslink Component is used to setup the radio connection on Crazyflies."); -} - -QString SyslinkComponent::iconResource(void) const -{ - return "/qmlimages/wifi.svg"; -} - -bool SyslinkComponent::requiresSetup(void) const -{ - return false; -} - -bool SyslinkComponent::setupComplete(void) const -{ - return true; -} - -QStringList SyslinkComponent::setupCompleteChangedTriggerList(void) const -{ - return QStringList(); -} - -QUrl SyslinkComponent::setupSource(void) const -{ - return QUrl::fromUserInput("qrc:/qml/SyslinkComponent.qml"); -} - -QUrl SyslinkComponent::summaryQmlSource(void) const -{ - return QUrl(); -} - -QString SyslinkComponent::prerequisiteSetup(void) const -{ - return QString(); -} diff --git a/src/AutoPilotPlugins/Common/SyslinkComponent.h b/src/AutoPilotPlugins/Common/SyslinkComponent.h index b4f961bb2d5..4d2b8a32885 100644 --- a/src/AutoPilotPlugins/Common/SyslinkComponent.h +++ b/src/AutoPilotPlugins/Common/SyslinkComponent.h @@ -16,23 +16,18 @@ class SyslinkComponent : public VehicleComponent { Q_OBJECT public: - SyslinkComponent (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr); - - // Virtuals from VehicleComponent - QStringList setupCompleteChangedTriggerList() const; - - // Virtuals from VehicleComponent - QString name () const; - QString description () const; - QString iconResource () const; - bool requiresSetup () const; - bool setupComplete () const; - QUrl setupSource () const; - QUrl summaryQmlSource () const; - QString prerequisiteSetup () const; - + explicit SyslinkComponent(Vehicle *vehicle, AutoPilotPlugin *autopilot, QObject *parent = nullptr); + + QStringList setupCompleteChangedTriggerList() const final { return QStringList(); } + QString name() const final { return _name; } + QString description() const final { return tr("The Syslink Component is used to setup the radio connection on Crazyflies."); } + QString iconResource() const final { return "/qmlimages/wifi.svg"; } + bool requiresSetup() const final { return false; } + bool setupComplete() const final { return true; } + QUrl setupSource() const final { return QUrl::fromUserInput("qrc:/qml/SyslinkComponent.qml"); } + QUrl summaryQmlSource() const final { return QUrl(); } + private: - const QString _name; - QVariantList _summaryItems; + const QString _name; + QVariantList _summaryItems; }; - diff --git a/src/AutoPilotPlugins/Common/SyslinkComponentController.cc b/src/AutoPilotPlugins/Common/SyslinkComponentController.cc index 97ab3df6c5e..0ea2e15edfe 100644 --- a/src/AutoPilotPlugins/Common/SyslinkComponentController.cc +++ b/src/AutoPilotPlugins/Common/SyslinkComponentController.cc @@ -11,123 +11,73 @@ #include "Vehicle.h" #include "QGCLoggingCategory.h" -QGC_LOGGING_CATEGORY(SyslinkComponentControllerLog, "SyslinkComponentControllerLog") - -//----------------------------------------------------------------------------- -SyslinkComponentController::SyslinkComponentController() +QGC_LOGGING_CATEGORY(SyslinkComponentControllerLog, "qgc.autopilotplugins.common.syslinkcomponentcontroller") + +SyslinkComponentController::SyslinkComponentController(QObject *parent) + : FactPanelController(parent) + , _chan(getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_CHAN"))) + , _rate(getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_RATE"))) + , _addr1(getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR1"))) + , _addr2(getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR2"))) { - _dataRates.append(QStringLiteral("750Kb/s")); - _dataRates.append(QStringLiteral("1Mb/s")); - _dataRates.append(QStringLiteral("2Mb/s")); + // qCDebug(SyslinkComponentControllerLog) << Q_FUNC_INFO << this; - Fact* chan = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_CHAN")); - connect(chan, &Fact::valueChanged, this, &SyslinkComponentController::_channelChanged); - Fact* rate = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_RATE")); - connect(rate, &Fact::valueChanged, this, &SyslinkComponentController::_rateChanged); - Fact* addr1 = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR1")); - connect(addr1, &Fact::valueChanged, this, &SyslinkComponentController::_addressChanged); - Fact* addr2 = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR2")); - connect(addr2, &Fact::valueChanged, this, &SyslinkComponentController::_addressChanged); + (void) connect(_chan, &Fact::valueChanged, this, &SyslinkComponentController::_channelChanged); + (void) connect(_rate, &Fact::valueChanged, this, &SyslinkComponentController::_rateChanged); + (void) connect(_addr1, &Fact::valueChanged, this, &SyslinkComponentController::_addressChanged); + (void) connect(_addr2, &Fact::valueChanged, this, &SyslinkComponentController::_addressChanged); } -//----------------------------------------------------------------------------- SyslinkComponentController::~SyslinkComponentController() { - + // qCDebug(SyslinkComponentControllerLog) << Q_FUNC_INFO << this; } -//----------------------------------------------------------------------------- -int -SyslinkComponentController::radioChannel() +int SyslinkComponentController::radioChannel() const { - return getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_CHAN"))->rawValue().toUInt(); + return _chan->rawValue().toUInt(); } -//----------------------------------------------------------------------------- -void -SyslinkComponentController::setRadioChannel(int num) +void SyslinkComponentController::setRadioChannel(int num) const { - Fact* f = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_CHAN")); - f->setRawValue(QVariant(num)); + _chan->setRawValue(QVariant(num)); } -//----------------------------------------------------------------------------- -QString -SyslinkComponentController::radioAddress() +QString SyslinkComponentController::radioAddress() const { - uint32_t val_uh = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR1"))->rawValue().toUInt(); - uint32_t val_lh = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR2"))->rawValue().toUInt(); - uint64_t val = (((uint64_t) val_uh) << 32) | ((uint64_t) val_lh); + const uint32_t val_uh = _addr1->rawValue().toUInt(); + const uint32_t val_lh = _addr2->rawValue().toUInt(); + const uint64_t val = ((static_cast(val_uh)) << 32) | static_cast(val_lh); - return QString().number(val, 16); + return QString::number(val, 16); } -//----------------------------------------------------------------------------- -void -SyslinkComponentController::setRadioAddress(QString str) +void SyslinkComponentController::setRadioAddress(const QString &str) const { - Fact *uh = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR1")); - Fact *lh = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR2")); - - uint64_t val = str.toULongLong(0, 16); - - uint32_t val_uh = val >> 32; - uint32_t val_lh = val & 0xFFFFFFFF; + const uint64_t val = str.toULongLong(0, 16); + const uint32_t val_uh = val >> 32; + const uint32_t val_lh = val & 0xFFFFFFFF; - uh->setRawValue(QVariant(val_uh)); - lh->setRawValue(QVariant(val_lh)); + _addr1->setRawValue(QVariant(val_uh)); + _addr2->setRawValue(QVariant(val_lh)); } -//----------------------------------------------------------------------------- -int -SyslinkComponentController::radioRate() +int SyslinkComponentController::radioRate() const { - return getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_RATE"))->rawValue().toInt(); + return _rate->rawValue().toInt(); } -//----------------------------------------------------------------------------- -void -SyslinkComponentController::setRadioRate(int idx) +void SyslinkComponentController::setRadioRate(int idx) const { - if(idx >= 0 && idx <= 2 && idx != radioRate()) { - Fact* r = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_RATE")); - r->setRawValue(idx); + if ((idx >= 0) && (idx <= 2) && (idx != radioRate())) { + _rate->setRawValue(idx); } } -//----------------------------------------------------------------------------- -void -SyslinkComponentController::resetDefaults() -{ - Fact* chan = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_CHAN")); - Fact* rate = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_RATE")); - Fact* addr1 = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR1")); - Fact* addr2 = getParameterFact(_vehicle->id(), QStringLiteral("SLNK_RADIO_ADDR2")); - - chan->setRawValue(chan->rawDefaultValue()); - rate->setRawValue(rate->rawDefaultValue()); - addr1->setRawValue(addr1->rawDefaultValue()); - addr2->setRawValue(addr2->rawDefaultValue()); -} - -//----------------------------------------------------------------------------- -void -SyslinkComponentController::_channelChanged(QVariant) +void SyslinkComponentController::resetDefaults() const { - emit radioChannelChanged(); + _chan->setRawValue(_chan->rawDefaultValue()); + _rate->setRawValue(_rate->rawDefaultValue()); + _addr1->setRawValue(_addr1->rawDefaultValue()); + _addr2->setRawValue(_addr2->rawDefaultValue()); } - -//----------------------------------------------------------------------------- -void -SyslinkComponentController::_addressChanged(QVariant) -{ - emit radioAddressChanged(); -} - -//----------------------------------------------------------------------------- -void -SyslinkComponentController::_rateChanged(QVariant) -{ - emit radioRateChanged(); -} - diff --git a/src/AutoPilotPlugins/Common/SyslinkComponentController.h b/src/AutoPilotPlugins/Common/SyslinkComponentController.h index cd76289edd8..cbef6db9905 100644 --- a/src/AutoPilotPlugins/Common/SyslinkComponentController.h +++ b/src/AutoPilotPlugins/Common/SyslinkComponentController.h @@ -9,58 +9,55 @@ #pragma once -#include "FactPanelController.h" - #include #include +#include "FactPanelController.h" + +class Fact; class Vehicle; Q_DECLARE_LOGGING_CATEGORY(SyslinkComponentControllerLog) -namespace Ui { - class SyslinkComponentController; -} - class SyslinkComponentController : public FactPanelController { Q_OBJECT - Q_MOC_INCLUDE("Vehicle.h") + Q_PROPERTY(int radioChannel READ radioChannel WRITE setRadioChannel NOTIFY radioChannelChanged) + Q_PROPERTY(QString radioAddress READ radioAddress WRITE setRadioAddress NOTIFY radioAddressChanged) + Q_PROPERTY(int radioRate READ radioRate WRITE setRadioRate NOTIFY radioRateChanged) + Q_PROPERTY(QStringList radioRates READ radioRates CONSTANT) public: - SyslinkComponentController (); - ~SyslinkComponentController (); - - Q_PROPERTY(int radioChannel READ radioChannel WRITE setRadioChannel NOTIFY radioChannelChanged) - Q_PROPERTY(QString radioAddress READ radioAddress WRITE setRadioAddress NOTIFY radioAddressChanged) - Q_PROPERTY(int radioRate READ radioRate WRITE setRadioRate NOTIFY radioRateChanged) - Q_PROPERTY(QStringList radioRates READ radioRates CONSTANT) - Q_PROPERTY(Vehicle* vehicle READ vehicle CONSTANT) - - Q_INVOKABLE void resetDefaults(); + explicit SyslinkComponentController(QObject *parent = nullptr); + ~SyslinkComponentController(); - int radioChannel (); - QString radioAddress (); - int radioRate (); - QStringList radioRates () { return _dataRates; } - Vehicle* vehicle () { return _vehicle; } + Q_INVOKABLE void resetDefaults() const; - void setRadioChannel (int num); - void setRadioAddress (QString str); - void setRadioRate (int idx); + int radioChannel() const; + QString radioAddress() const; + int radioRate() const; + QStringList radioRates() const { return _dataRates; } + Vehicle *vehicle() const { return _vehicle; } + void setRadioChannel(int num) const; + void setRadioAddress(const QString &str) const; + void setRadioRate(int idx) const; signals: - void radioChannelChanged (); - void radioAddressChanged (); - void radioRateChanged (); + void radioChannelChanged(); + void radioAddressChanged(); + void radioRateChanged(); private slots: - void _channelChanged (QVariant value); - void _addressChanged (QVariant value); - void _rateChanged (QVariant value); + void _channelChanged(QVariant value) { Q_UNUSED(value); emit radioChannelChanged(); } + void _addressChanged(QVariant value) { Q_UNUSED(value); emit radioAddressChanged(); } + void _rateChanged(QVariant value) { Q_UNUSED(value); emit radioRateChanged(); } private: - QStringList _dataRates; + const QStringList _dataRates = { QStringLiteral("750Kb/s"), QStringLiteral("1Mb/s"), QStringLiteral("2Mb/s") }; + Fact *_chan = nullptr; + Fact *_rate = nullptr; + Fact *_addr1 = nullptr; + Fact *_addr2 = nullptr; }; diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc index a05fe51df58..aa832979c1f 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc @@ -7,29 +7,17 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - #include "GenericAutoPilotPlugin.h" -GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : - AutoPilotPlugin(vehicle, parent) +GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle *vehicle, QObject *parent) + : AutoPilotPlugin(vehicle, parent) { - if (!vehicle) { - qWarning() << "Internal error"; - } + } -const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) +const QVariantList& GenericAutoPilotPlugin::vehicleComponents() { static QVariantList emptyList; - - return emptyList; -} -QString GenericAutoPilotPlugin:: prerequisiteSetup(VehicleComponent* component) const -{ - Q_UNUSED(component); - return QString(); + return emptyList; } diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h index 35603d5deeb..6f96edc7bce 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h @@ -12,19 +12,15 @@ #include "AutoPilotPlugin.h" -/// @file -/// @brief This is the generic implementation of the AutoPilotPlugin class for mavs -/// we do not have a specific AutoPilotPlugin implementation. -/// @author Don Gagne - +/// This is the generic implementation of the AutoPilotPlugin class for mavs +/// we do not have a specific AutoPilotPlugin implementation. class GenericAutoPilotPlugin : public AutoPilotPlugin { Q_OBJECT public: - GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent = nullptr); - - // Overrides from AutoPilotPlugin - const QVariantList& vehicleComponents(void) final; - QString prerequisiteSetup(VehicleComponent* component) const final; + explicit GenericAutoPilotPlugin(Vehicle *vehicle, QObject *parent = nullptr); + + const QVariantList &vehicleComponents() final; + QString prerequisiteSetup(VehicleComponent *component) const final { Q_UNUSED(component); return QString(); } }; diff --git a/src/AutoPilotPlugins/VehicleComponent.cc b/src/AutoPilotPlugins/VehicleComponent.cc index 8c4fa9f5927..9af8d803762 100644 --- a/src/AutoPilotPlugins/VehicleComponent.cc +++ b/src/AutoPilotPlugins/VehicleComponent.cc @@ -7,66 +7,64 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - #include "VehicleComponent.h" #include "ParameterManager.h" +#include "QGCLoggingCategory.h" #include "Vehicle.h" #include #include -VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent, QObject* parent) - : QObject (parent) - , _vehicle (vehicle) - , _autopilot (autopilot) - , _KnownVehicleComponent (KnownVehicleComponent) +QGC_LOGGING_CATEGORY(VehicleComponentLog, "qgc.autopilotplugin.vehiclecomponent"); + +VehicleComponent::VehicleComponent(Vehicle *vehicle, AutoPilotPlugin *autopilot, AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent, QObject *parent) + : QObject(parent) + , _vehicle(vehicle) + , _autopilot(autopilot) + , _KnownVehicleComponent(KnownVehicleComponent) { + // qCDebug(VehicleComponentLog) << Q_FUNC_INFO << this; + if (!vehicle || !autopilot) { - qWarning() << "Internal error"; + qCWarning(VehicleComponentLog) << "Internal error"; } } VehicleComponent::~VehicleComponent() { - + // qCDebug(VehicleComponentLog) << Q_FUNC_INFO << this; } -void VehicleComponent::addSummaryQmlComponent(QQmlContext* context, QQuickItem* parent) +void VehicleComponent::addSummaryQmlComponent(QQmlContext *context, QQuickItem *parent) { - if (context) { - // FIXME: We own this object now, need to delete somewhere - QQmlComponent component(context->engine(), QUrl::fromUserInput("qrc:/qml/VehicleComponentSummaryButton.qml")); - if (component.status() == QQmlComponent::Error) { - qWarning() << component.errors(); - } else { - QQuickItem* item = qobject_cast(component.create(context)); - if (item) { - item->setParentItem(parent); - item->setProperty("vehicleComponent", QVariant::fromValue(this)); - } else { - qWarning() << "Internal error"; - } - } - } else { - qWarning() << "Internal error"; + if (!context) { + qCWarning(VehicleComponentLog) << "Internal error"; + return; + } + + QQmlComponent component = new QQmlComponent(context->engine(), QUrl::fromUserInput("qrc:/qml/VehicleComponentSummaryButton.qml"), this); + if (component.status() == QQmlComponent::Error) { + qCWarning(VehicleComponentLog) << component.errors(); + return; } + + QQuickItem *const item = qobject_cast(component.create(context)); + if (!item) { + qCWarning(VehicleComponentLog) << "Internal error"; + return; + } + + item->setParentItem(parent); + item->setProperty("vehicleComponent", QVariant::fromValue(this)); } -void VehicleComponent::setupTriggerSignals(void) +void VehicleComponent::setupTriggerSignals() { // Watch for changed on trigger list params for (const QString ¶mName: setupCompleteChangedTriggerList()) { if (_vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, paramName)) { - Fact* fact = _vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, paramName); - connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated); + Fact *const fact = _vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, paramName); + (void) connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated); } } } - -void VehicleComponent::_triggerUpdated(QVariant /*value*/) -{ - emit setupCompleteChanged(); -} diff --git a/src/AutoPilotPlugins/VehicleComponent.h b/src/AutoPilotPlugins/VehicleComponent.h index ea40ca43a0d..93532a2141f 100644 --- a/src/AutoPilotPlugins/VehicleComponent.h +++ b/src/AutoPilotPlugins/VehicleComponent.h @@ -9,74 +9,76 @@ #pragma once -#include "AutoPilotPlugin.h" - +#include #include +#include #include #include -#include + +#include "AutoPilotPlugin.h" class Vehicle; class QQuickItem; class QQmlContext; +Q_DECLARE_LOGGING_CATEGORY(VehicleComponentLog) + /// A vehicle component is an object which abstracts the physical portion of a vehicle into a set of /// configurable values and user interface. - class VehicleComponent : public QObject { Q_OBJECT - - Q_PROPERTY(QString name READ name CONSTANT) - Q_PROPERTY(QString description READ description CONSTANT) - Q_PROPERTY(bool requiresSetup READ requiresSetup CONSTANT) - Q_PROPERTY(bool setupComplete READ setupComplete STORED false NOTIFY setupCompleteChanged) - Q_PROPERTY(QString iconResource READ iconResource CONSTANT) - Q_PROPERTY(QUrl setupSource READ setupSource NOTIFY setupSourceChanged) - Q_PROPERTY(QUrl summaryQmlSource READ summaryQmlSource CONSTANT) - Q_PROPERTY(bool allowSetupWhileArmed READ allowSetupWhileArmed CONSTANT) - Q_PROPERTY(bool allowSetupWhileFlying READ allowSetupWhileFlying CONSTANT) - Q_PROPERTY(AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent READ KnownVehicleComponent CONSTANT) + + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QString description READ description CONSTANT) + Q_PROPERTY(bool requiresSetup READ requiresSetup CONSTANT) + Q_PROPERTY(bool setupComplete READ setupComplete STORED false NOTIFY setupCompleteChanged) + Q_PROPERTY(QString iconResource READ iconResource CONSTANT) + Q_PROPERTY(QUrl setupSource READ setupSource NOTIFY setupSourceChanged) + Q_PROPERTY(QUrl summaryQmlSource READ summaryQmlSource CONSTANT) + Q_PROPERTY(bool allowSetupWhileArmed READ allowSetupWhileArmed CONSTANT) + Q_PROPERTY(bool allowSetupWhileFlying READ allowSetupWhileFlying CONSTANT) + Q_PROPERTY(AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent READ KnownVehicleComponent CONSTANT) public: - VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent, QObject* parent = nullptr); - ~VehicleComponent(); - - virtual QString name(void) const = 0; - virtual QString description(void) const = 0; - virtual QString iconResource(void) const = 0; - virtual bool requiresSetup(void) const = 0; - virtual bool setupComplete(void) const = 0; - virtual QUrl setupSource(void) const = 0; - virtual QUrl summaryQmlSource(void) const = 0; + explicit VehicleComponent(Vehicle *vehicle, AutoPilotPlugin *autopilot, AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent, QObject *parent = nullptr); + virtual ~VehicleComponent(); + + virtual QString name() const = 0; + virtual QString description() const = 0; + virtual QString iconResource() const = 0; + virtual bool requiresSetup() const = 0; + virtual bool setupComplete() const = 0; + virtual QUrl setupSource() const = 0; + virtual QUrl summaryQmlSource() const = 0; // @return true: Setup panel can be shown while vehicle is armed - virtual bool allowSetupWhileArmed(void) const { return false; } // Defaults to false - + virtual bool allowSetupWhileArmed() const { return false; } + // @return true: Setup panel can be shown while vehicle is flying (and armed) - virtual bool allowSetupWhileFlying(void) const { return false; } // Defaults to false + virtual bool allowSetupWhileFlying() const { return false; } virtual void addSummaryQmlComponent(QQmlContext* context, QQuickItem* parent); - - /// @brief Returns an list of parameter names for which a change should cause the setupCompleteChanged - /// signal to be emitted. - virtual QStringList setupCompleteChangedTriggerList(void) const = 0; + + /// Returns an list of parameter names for which a change should cause the setupCompleteChanged + /// signal to be emitted. + virtual QStringList setupCompleteChangedTriggerList() const = 0; /// Should be called after the component is created (but not in constructor) to setup the /// signals which are used to track parameter changes which affect setupComplete state. - virtual void setupTriggerSignals(void); + virtual void setupTriggerSignals(); - AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent(void) const { return _KnownVehicleComponent; } + AutoPilotPlugin::KnownVehicleComponent KnownVehicleComponent() const { return _KnownVehicleComponent; } signals: - void setupCompleteChanged (void); - void setupSourceChanged (void); + void setupCompleteChanged(); + void setupSourceChanged(); protected slots: - void _triggerUpdated(QVariant value); + void _triggerUpdated(QVariant value) { emit setupCompleteChanged(); } protected: - Vehicle* _vehicle; - AutoPilotPlugin* _autopilot; - AutoPilotPlugin::KnownVehicleComponent _KnownVehicleComponent; + Vehicle *_vehicle = nullptr; + AutoPilotPlugin *_autopilot = nullptr; + AutoPilotPlugin::KnownVehicleComponent _KnownVehicleComponent; };