diff --git a/files/images/px4/calibration/radioCenter.png b/files/images/px4/calibration/radioCenter.png new file mode 100644 index 0000000000000000000000000000000000000000..556321ec4b1c3142dc40acaf8068b4fb57e923a5 Binary files /dev/null and b/files/images/px4/calibration/radioCenter.png differ diff --git a/files/images/px4/calibration/radioHome.png b/files/images/px4/calibration/radioHome.png new file mode 100644 index 0000000000000000000000000000000000000000..b335193bc5b71c8f4080a90e0a0d086d49fb6243 Binary files /dev/null and b/files/images/px4/calibration/radioHome.png differ diff --git a/files/images/px4/calibration/radioPitchDown.png b/files/images/px4/calibration/radioPitchDown.png new file mode 100644 index 0000000000000000000000000000000000000000..dc1d75dab4a4f7209bd3d8762e9e715b9cb516f0 Binary files /dev/null and b/files/images/px4/calibration/radioPitchDown.png differ diff --git a/files/images/px4/calibration/radioPitchUp.png b/files/images/px4/calibration/radioPitchUp.png new file mode 100644 index 0000000000000000000000000000000000000000..90d06ed0d59092173c1a182e78a9d97c27877fc8 Binary files /dev/null and b/files/images/px4/calibration/radioPitchUp.png differ diff --git a/files/images/px4/calibration/radioRollLeft.png b/files/images/px4/calibration/radioRollLeft.png new file mode 100644 index 0000000000000000000000000000000000000000..6949dcd2b10048721b75e0e241c62393b11d01e6 Binary files /dev/null and b/files/images/px4/calibration/radioRollLeft.png differ diff --git a/files/images/px4/calibration/radioRollRight.png b/files/images/px4/calibration/radioRollRight.png new file mode 100644 index 0000000000000000000000000000000000000000..18cfbbe382efbe3cae5e48d364126c3dc597d105 Binary files /dev/null and b/files/images/px4/calibration/radioRollRight.png differ diff --git a/files/images/px4/calibration/radioSwitchMinMax.png b/files/images/px4/calibration/radioSwitchMinMax.png new file mode 100644 index 0000000000000000000000000000000000000000..fb284219df1c7158b4c5b9f5b9d7a5ef6004cb50 Binary files /dev/null and b/files/images/px4/calibration/radioSwitchMinMax.png differ diff --git a/files/images/px4/calibration/radioThrottleDown.png b/files/images/px4/calibration/radioThrottleDown.png new file mode 100644 index 0000000000000000000000000000000000000000..b335193bc5b71c8f4080a90e0a0d086d49fb6243 Binary files /dev/null and b/files/images/px4/calibration/radioThrottleDown.png differ diff --git a/files/images/px4/calibration/radioThrottleUp.png b/files/images/px4/calibration/radioThrottleUp.png new file mode 100644 index 0000000000000000000000000000000000000000..86f7ae1586f06c4613339d75ecbc2b224a61b6d1 Binary files /dev/null and b/files/images/px4/calibration/radioThrottleUp.png differ diff --git a/files/images/px4/calibration/radioYawLeft.png b/files/images/px4/calibration/radioYawLeft.png new file mode 100644 index 0000000000000000000000000000000000000000..575aec84d51ba61610d28e7d6a6cf439efa76180 Binary files /dev/null and b/files/images/px4/calibration/radioYawLeft.png differ diff --git a/files/images/px4/calibration/radioYawRight.png b/files/images/px4/calibration/radioYawRight.png new file mode 100644 index 0000000000000000000000000000000000000000..9367b35b22108bfb692218ddb9a0fe68692dd148 Binary files /dev/null and b/files/images/px4/calibration/radioYawRight.png differ diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 07e6c799b1cc6edecba4e3d2dedfe956ddafb6db..e098a61c0bb039417ede6c1101c26082acd1b941 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -489,6 +489,7 @@ HEADERS += \ src/ui/px4_configuration/QGCPX4MulticopterConfig.h \ src/ui/px4_configuration/QGCPX4SensorCalibration.h \ src/ui/px4_configuration/PX4RCCalibration.h \ + src/ui/px4_configuration/RCValueWidget.h \ src/ui/px4_configuration/PX4Bootloader.h \ src/ui/px4_configuration/PX4FirmwareUpgradeThread.h \ src/ui/px4_configuration/PX4FirmwareUpgrade.h \ @@ -646,6 +647,7 @@ SOURCES += \ src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \ src/ui/px4_configuration/QGCPX4SensorCalibration.cc \ src/ui/px4_configuration/PX4RCCalibration.cc \ + src/ui/px4_configuration/RCValueWidget.cc \ src/ui/px4_configuration/PX4Bootloader.cc \ src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc \ src/ui/px4_configuration/PX4FirmwareUpgrade.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 5a7d9cdaece71becfacb7e7e073d8eabee05eec4..ee2f4254acea26e25284b4f7b809c646fe108b65 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -175,6 +175,17 @@ files/images/px4/calibration/accel_z-.png files/images/px4/calibration/accel_y+.png files/images/px4/calibration/mag_calibration_figure8.png + files/images/px4/calibration/radioCenter.png + files/images/px4/calibration/radioHome.png + files/images/px4/calibration/radioRollLeft.png + files/images/px4/calibration/radioRollRight.png + files/images/px4/calibration/radioPitchUp.png + files/images/px4/calibration/radioPitchDown.png + files/images/px4/calibration/radioYawLeft.png + files/images/px4/calibration/radioYawRight.png + files/images/px4/calibration/radioThrottleUp.png + files/images/px4/calibration/radioThrottleDown.png + files/images/px4/calibration/radioSwitchMinMax.png files/images/px4/menu/sensors.png files/images/px4/menu/firmware_upgrade.png files/images/px4/menu/plane.png diff --git a/src/qgcunittest/PX4RCCalibrationTest.cc b/src/qgcunittest/PX4RCCalibrationTest.cc index 88b4684215383a8bd898e9c12b15b79250ae44d1..c6696739b56382c89030eae63e70291760a2a94b 100644 --- a/src/qgcunittest/PX4RCCalibrationTest.cc +++ b/src/qgcunittest/PX4RCCalibrationTest.cc @@ -36,14 +36,12 @@ { \ if (_nextButton->isEnabled() != !!((mask) & nextButtonMask) || \ _skipButton->isEnabled() != !!((mask) & skipButtonMask) || \ - _cancelButton->isEnabled() != !!((mask) & cancelButtonMask) || \ - _tryAgainButton->isEnabled() != !!((mask) & tryAgainButtonMask)) { \ + _cancelButton->isEnabled() != !!((mask) & cancelButtonMask) ) { \ qDebug() << _statusLabel->text(); \ } \ QCOMPARE(_nextButton->isEnabled(), !!((mask) & nextButtonMask)); \ QCOMPARE(_skipButton->isEnabled(), !!((mask) & skipButtonMask)); \ QCOMPARE(_cancelButton->isEnabled(), !!((mask) & cancelButtonMask)); \ - QCOMPARE(_tryAgainButton->isEnabled(), !!((mask) & tryAgainButtonMask)); \ } // This allows you to write unit tests which will click the Cancel button the first time through, followed @@ -60,75 +58,74 @@ } \ } +const int PX4RCCalibrationTest::_stickSettleWait = PX4RCCalibration::_stickDetectSettleMSecs * 1.5; + const int PX4RCCalibrationTest::_testMinValue = PX4RCCalibration::_rcCalPWMDefaultMinValue + 10; const int PX4RCCalibrationTest::_testMaxValue = PX4RCCalibration::_rcCalPWMDefaultMaxValue - 10; -const int PX4RCCalibrationTest::_testTrimValue = PX4RCCalibration::_rcCalPWMDefaultTrimValue + 10; -const int PX4RCCalibrationTest::_testThrottleTrimValue = PX4RCCalibration::_rcCalPWMDefaultMinValue + 10; +const int PX4RCCalibrationTest::_testCenterValue = PX4RCCalibrationTest::_testMinValue + ((PX4RCCalibrationTest::_testMaxValue - PX4RCCalibrationTest::_testMinValue) / 2); /// @brief Maps from function index to channel index. -1 signals no mapping. Channel indices are offset 1 from function index /// to catch bugs where function index is incorrectly used as channel index. -const int PX4RCCalibrationTest::_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionMax]= { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, -1 }; +const int PX4RCCalibrationTest::_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionMax]= { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11 }; -const struct PX4RCCalibrationTest::ChannelSettings PX4RCCalibrationTest::_rgChannelSettingsPreValidate[PX4RCCalibrationTest::_availableChannels] = { - // Function Min Value Max Value Trim Value Reversed MinMaxShown MinValid MaxValid +const struct PX4RCCalibrationTest::ChannelSettings PX4RCCalibrationTest::_rgChannelSettings[PX4RCCalibrationTest::_availableChannels] = { + // Function Min Max # Reversed // Channel 0 : Not mapped to function, Simulate invalid Min/Max - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, false }, - - // Channels 1-10 are mapped to all available modes, except for Aux2 which is skipped - { PX4RCCalibration::rcCalFunctionRoll, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testTrimValue, true, true, true, true }, - { PX4RCCalibration::rcCalFunctionPitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionYaw, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testTrimValue, true, true, true, true }, - { PX4RCCalibration::rcCalFunctionThrottle, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testThrottleTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionModeSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionPosCtlSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionLoiterSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionReturnSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionFlaps, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionAux1, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, + { PX4RCCalibration::rcCalFunctionMax, _testCenterValue, _testCenterValue, 0, false }, - // Channel 11 : Not mapped to function, Simulate invalid Min/Max - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, false }, + // Channels 1-11 are mapped to all available modes + { PX4RCCalibration::rcCalFunctionRoll, _testMinValue, _testMaxValue, 0, true }, + { PX4RCCalibration::rcCalFunctionPitch, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionYaw, _testMinValue, _testMaxValue, 0, true }, + { PX4RCCalibration::rcCalFunctionThrottle, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionModeSwitch, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionPosCtlSwitch, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionLoiterSwitch, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionReturnSwitch, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionFlaps, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionAux1, _testMinValue, _testMaxValue, 0, false }, + { PX4RCCalibration::rcCalFunctionAux2, _testMinValue, _testMaxValue, 0, false }, // Channel 12 : Not mapped to function, Simulate invalid Min, valid Max - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, true }, + { PX4RCCalibration::rcCalFunctionMax, _testCenterValue, _testMaxValue, 0, false }, // Channel 13 : Not mapped to function, Simulate valid Min, invalid Max - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, false }, + { PX4RCCalibration::rcCalFunctionMax, _testMinValue, _testCenterValue, 0, false }, // Channels 14-17: Not mapped to function, Simulate invalid Min/Max, since available channel Min/Max is still shown - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, false }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, false }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, false }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, false, false }, + { PX4RCCalibration::rcCalFunctionMax, _testCenterValue, _testCenterValue, 0, false }, + { PX4RCCalibration::rcCalFunctionMax, _testCenterValue, _testCenterValue, 0, false }, + { PX4RCCalibration::rcCalFunctionMax, _testCenterValue, _testCenterValue, 0, false }, + { PX4RCCalibration::rcCalFunctionMax, _testCenterValue, _testCenterValue, 0, false }, }; -const struct PX4RCCalibrationTest::ChannelSettings PX4RCCalibrationTest::_rgChannelSettingsPostValidate[PX4RCCalibration::_chanMax] = { - // Function Min Value Max Value Trim Value Reversed MinMaxShown MinValid MaxValid +const struct PX4RCCalibrationTest::ChannelSettings PX4RCCalibrationTest::_rgChannelSettingsValidate[PX4RCCalibration::_chanMax] = { + // Function Min Value Max Value Trim Value Reversed // Channel 0 is not mapped and should be defaulted - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, - // Channels 1-10 are mapped to all available modes, except for Aux2 which is skipped - { PX4RCCalibration::rcCalFunctionRoll, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testTrimValue, true, true, true, true }, - { PX4RCCalibration::rcCalFunctionPitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionYaw, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testTrimValue, true, true, true, true }, - { PX4RCCalibration::rcCalFunctionThrottle, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibrationTest::_testThrottleTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionModeSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionPosCtlSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionLoiterSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionReturnSwitch, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionFlaps, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionAux1, PX4RCCalibrationTest::_testMinValue, PX4RCCalibrationTest::_testMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false, true, true, true }, + // Channels 1-11 are mapped to all available modes + { PX4RCCalibration::rcCalFunctionRoll, _testMinValue, _testMaxValue, _testCenterValue, true }, + { PX4RCCalibration::rcCalFunctionPitch, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionYaw, _testMinValue, _testMaxValue, _testCenterValue, true }, + { PX4RCCalibration::rcCalFunctionThrottle, _testMinValue, _testMaxValue, _testMinValue, false }, + { PX4RCCalibration::rcCalFunctionModeSwitch, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionPosCtlSwitch, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionLoiterSwitch, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionReturnSwitch, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionFlaps, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionAux1, _testMinValue, _testMaxValue, _testCenterValue, false }, + { PX4RCCalibration::rcCalFunctionAux2, _testMinValue, _testMaxValue, _testCenterValue, false }, - // Channels 11-17 are not mapped and should be set to defaults - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, - { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMDefaultTrimValue, false, true, true, true }, + // Channels 12-17 are not mapped and should be set to defaults + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, + { PX4RCCalibration::rcCalFunctionMax, PX4RCCalibration::_rcCalPWMDefaultMinValue, PX4RCCalibration::_rcCalPWMDefaultMaxValue, PX4RCCalibration::_rcCalPWMCenterPoint, false }, }; PX4RCCalibrationTest::PX4RCCalibrationTest(void) : @@ -144,11 +141,10 @@ void PX4RCCalibrationTest::initTestCase(void) for (int function=0; function_setUnitTestMode(); + _calWidget->setVisible(true); _mockUASManager->setMockActiveUAS(_mockUAS); @@ -171,39 +169,44 @@ void PX4RCCalibrationTest::init(void) _cancelButton = _calWidget->findChild("rcCalCancel"); _nextButton = _calWidget->findChild("rcCalNext"); _skipButton = _calWidget->findChild("rcCalSkip"); - _tryAgainButton = _calWidget->findChild("rcCalTryAgain"); Q_ASSERT(_cancelButton); Q_ASSERT(_nextButton); Q_ASSERT(_skipButton); - Q_ASSERT(_tryAgainButton); _statusLabel = _calWidget->findChild("rcCalStatus"); Q_ASSERT(_statusLabel); for (size_t i=0; ifindChild(radioWidgetName.arg(i+1)); + QString radioWidgetName("channel%1Value"); + + RCValueWidget* radioWidget = _calWidget->findChild(radioWidgetName.arg(i+1)); Q_ASSERT(radioWidget); - _rgRadioWidget[i] = radioWidget; + _rgValueWidget[i] = radioWidget; } + + _rgSignals[0] = SIGNAL(nextButtonMessageBoxDisplayed()); + _multiSpyNextButtonMessageBox = new MultiSignalSpy(); + Q_CHECK_PTR(_multiSpyNextButtonMessageBox); + QCOMPARE(_multiSpyNextButtonMessageBox->init(_calWidget, _rgSignals, 1), true); + + QCOMPARE(_calWidget->_currentStep, -1); } void PX4RCCalibrationTest::cleanup(void) { + Q_ASSERT(_calWidget); + delete _calWidget; + Q_ASSERT(_mockUAS); delete _mockUAS; UASManager::setMockUASManager(NULL); - + Q_ASSERT(_mockUASManager); delete _mockUASManager; - Q_ASSERT(_calWidget); - delete _calWidget; } /// @brief Tests for correct behavior when active UAS is set into widget. @@ -217,7 +220,7 @@ void PX4RCCalibrationTest::_setUAS_test(void) QCOMPARE(_calWidget->isEnabled(), false); } -/// @brief Test for correct behavior in determining minimum numbers of channels for fligth. +/// @brief Test for correct behavior in determining minimum numbers of channels for flight. void PX4RCCalibrationTest::_minRCChannels_test(void) { // Next button won't be enabled until we see the minimum number of channels. @@ -228,373 +231,218 @@ void PX4RCCalibrationTest::_minRCChannels_test(void) QCOMPARE(_calWidget->_chanCount, chan+1); // Validate Next button state + QTest::mouseClick(_nextButton, Qt::LeftButton); + bool signalFound = _multiSpyNextButtonMessageBox->waitForSignalByIndex(0, 200); if (chan == PX4RCCalibration::_chanMinimum - 1) { - // Last channel should trigger enable - CHK_BUTTONS(nextButtonMask); + // Last channel should trigger Calibration available + QCOMPARE(signalFound, false); + QCOMPARE(_calWidget->_currentStep, 0); } else { - // Still less than the minimum channels - CHK_BUTTONS(0); + // Still less than the minimum channels. Next button should show message box. Calibration should not start. + QCOMPARE(signalFound, true); + QCOMPARE(_calWidget->_currentStep, -1); } + _multiSpyNextButtonMessageBox->clearAllSignals(); - // Only available channels should have enabled widget. A ui update cycle needs to have passed so we wait a little. + // Only available channels should have visible widget. A ui update cycle needs to have passed so we wait a little. QTest::qWait(PX4RCCalibration::_updateInterval * 2); for (int chanWidget=0; chanWidgetisEnabled(), !!(chanWidget <= chan)); + //qDebug() << _rgValueWidget[chanWidget]->objectName() << chanWidget << chan; + QCOMPARE(_rgValueWidget[chanWidget]->isVisible(), !!(chanWidget <= chan)); } } } -void PX4RCCalibrationTest::_beginState_worker(enum TestMode mode) +void PX4RCCalibrationTest::_beginCalibration(void) { - bool tryCancel1 = true; - -StartOver: - if (mode == testModeStandalone || mode == testModePrerequisite) { - _centerChannels(); - - _calWidget->_unitTestForceCalState(PX4RCCalibration::rcCalStateBegin); - } - - // Next button is always enabled in this state CHK_BUTTONS(nextButtonMask | cancelButtonMask); - // Click the next button: - // We should now be waiting for movement on a channel to identify the first RC function. The Next button will stay - // disabled until the sticks are moved enough to identify the channel. For required functions the Skip button is - // disabled. - NEXT_OR_CANCEL(1); - QCOMPARE(_calWidget->_rcCalState, PX4RCCalibration::rcCalStateIdentify); + // We should already have enough channels to proceed with calibration. Click next to start the process. + + QTest::mouseClick(_nextButton, Qt::LeftButton); + QCOMPARE(_calWidget->_currentStep, 1); CHK_BUTTONS(cancelButtonMask); } -void PX4RCCalibrationTest::_beginState_test(void) +void PX4RCCalibrationTest::_stickMoveWaitForSettle(int channel, int value) { - _beginState_worker(testModeStandalone); + //qDebug() << "_stickMoveWaitForSettle channel:value" << channel << value; + + // Move the stick, this will initialized the settle checker + _mockUAS->emitRemoteControlChannelRawChanged(channel, value); + + // Emit the signal again to start the settle timer + _mockUAS->emitRemoteControlChannelRawChanged(channel, value); + + // Wait long enough for the settle timer to expire + QTest::qWait(PX4RCCalibration::_stickDetectSettleMSecs * 1.5); + + // Emit the signal again so that we detect stick settle + _mockUAS->emitRemoteControlChannelRawChanged(channel, value); } -void PX4RCCalibrationTest::_identifyState_worker(enum TestMode mode) +void PX4RCCalibrationTest::_stickMoveAutoStep(const char* functionStr, enum PX4RCCalibration::rcCalFunctions function, enum PX4RCCalibrationTest::MoveToDirection direction, bool identifyStep) { - bool tryCancel1 = true; + Q_UNUSED(functionStr); + //qDebug() << "_stickMoveAutoStep function:direction:reversed:identifyStep" << functionStr << function << direction << identifyStep; -StartOver: - if (mode == testModeStandalone || mode == testModePrerequisite) - { - _centerChannels(); - - _calWidget->_unitTestForceCalState(PX4RCCalibration::rcCalStateIdentify); - - } + CHK_BUTTONS(cancelButtonMask); + + int channel = _rgFunctionChannelMap[function]; + int saveStep = _calWidget->_currentStep; + + bool reversed = _rgChannelSettings[channel].reversed; - // Loop over all function identifying mapped channels - for (int function=0; function= PX4RCCalibration::_chanMax) { + otherChannel = 0; } - // Move channel less than delta to make sure function is not identified - _mockUAS->emitRemoteControlChannelRawChanged(channelIndex, (float)PX4RCCalibration::_rcCalPWMCenterPoint + (PX4RCCalibration::_rcCalMoveDelta - 2.0f)); - CHK_BUTTONS(cancelButtonMask | skipMask); - - if (function != 0) { - // Try to assign a function index 0 channel to more than one function. This is not allowed so Next button should not enable. - _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[0], (float)PX4RCCalibration::_rcCalPWMValidMinValue); - _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[0], (float)PX4RCCalibration::_rcCalPWMValidMaxValue); - CHK_BUTTONS(cancelButtonMask | skipMask); - } - - if (tryCancel1) { - NEXT_OR_CANCEL(1); - } + _stickMoveWaitForSettle(otherChannel, _testMinValue); + QCOMPARE(_calWidget->_currentStep, saveStep); + CHK_BUTTONS(cancelButtonMask); - // Move channel larger than delta to identify channel. We should now be sitting in a found state. - _mockUAS->emitRemoteControlChannelRawChanged(channelIndex, (float)PX4RCCalibration::_rcCalPWMCenterPoint + (PX4RCCalibration::_rcCalMoveDelta + 2.0f)); - CHK_BUTTONS(cancelButtonMask | tryAgainButtonMask | nextButtonMask); - - NEXT_OR_CANCEL(1); + _stickMoveWaitForSettle(otherChannel, PX4RCCalibration::_rcCalPWMCenterPoint); + QCOMPARE(_calWidget->_currentStep, saveStep); + CHK_BUTTONS(cancelButtonMask); } - // We should now be waiting for min/max values. - QCOMPARE(_calWidget->_rcCalState, PX4RCCalibration::rcCalStateMinMax); - CHK_BUTTONS(nextButtonMask | cancelButtonMask); - - if (mode == testModeStandalone) { - _calWidget->_writeCalibration(false /* !trimsOnly */); - _validateParameters(validateMappingMask); + // Move channel to specified position to trigger next step + + int value; + if (direction == moveToMin) { + value = reversed ? _testMaxValue : _testMinValue; + } else if (direction == moveToMax) { + value = reversed ? _testMinValue : _testMaxValue; + } else if (direction == moveToCenter) { + value = PX4RCCalibration::_rcCalPWMCenterPoint; + } else { + Q_ASSERT(false); } + + _stickMoveWaitForSettle(channel, value); + QCOMPARE(_calWidget->_currentStep, saveStep + 1); } -void PX4RCCalibrationTest::_identifyState_test(void) -{ - _identifyState_worker(testModeStandalone); -} - -void PX4RCCalibrationTest::_minMaxState_worker(enum TestMode mode) +void PX4RCCalibrationTest::_switchMinMaxStep(void) { - bool tryCancel1 = true; - -StartOver: - if (mode == testModeStandalone || mode == testModePrerequisite) { - // The Min/Max calibration updates the radio channel ui widgets with the min/max values for all mapped channels. - // In order for those adio channel ui widgets to be updated correctly those functions must be alread mapped to a - // channel. So we have to run the _identifyState_test first to set up the internal state correctly. - _identifyState_worker(testModePrerequisite); - - _centerChannels(); - - _calWidget->_unitTestForceCalState(PX4RCCalibration::rcCalStateMinMax); - - // We should now be waiting for min/max values. - CHK_BUTTONS(nextButtonMask | cancelButtonMask); - } - - // Before we start sending rc values the widgets should all have min/max as invalid - for (int chan=0; chanisMinValid(), false); - QCOMPARE(_rgRadioWidget[chan]->isMaxValid(), false); - } + CHK_BUTTONS(nextButtonMask | cancelButtonMask); // Try setting a min/max value that is below the threshold to make sure min/max doesn't go valid _mockUAS->emitRemoteControlChannelRawChanged(0, (float)(PX4RCCalibration::_rcCalPWMValidMinValue + 1)); _mockUAS->emitRemoteControlChannelRawChanged(0, (float)(PX4RCCalibration::_rcCalPWMValidMaxValue - 1)); - QCOMPARE(_rgRadioWidget[0]->isMinValid(), false); - QCOMPARE(_rgRadioWidget[0]->isMaxValid(), false); - - // Send min/max values for all channels + QCOMPARE(_rgValueWidget[0]->isMinValid(), false); + QCOMPARE(_rgValueWidget[0]->isMaxValid(), false); + + // Send min/max values switch channels for (int chan=0; chan<_availableChannels; chan++) { - //qDebug() << chan << _rgChannelSettingsPreValidate[chan].rcMin << _rgChannelSettingsPreValidate[chan].rcMax; - _mockUAS->emitRemoteControlChannelRawChanged(chan, (float)_rgChannelSettingsPreValidate[chan].rcMin); - _mockUAS->emitRemoteControlChannelRawChanged(chan, (float)_rgChannelSettingsPreValidate[chan].rcMax); - - // Re-Center to not screw up next state - _mockUAS->emitRemoteControlChannelRawChanged(chan, (float)PX4RCCalibration::_rcCalPWMCenterPoint); + //qDebug() << chan << _rgChannelSettingsPreValidate[chan].rcMin << _rgChannelSettingsPreValidate[chan].rcMax; + _mockUAS->emitRemoteControlChannelRawChanged(chan, _rgChannelSettings[chan].rcMin); + _mockUAS->emitRemoteControlChannelRawChanged(chan, _rgChannelSettings[chan].rcMax); } - - _validateWidgets(validateMinMaxMask, _rgChannelSettingsPreValidate); - // Make sure throttle is at min - _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionThrottle], (float)PX4RCCalibration::_rcCalPWMValidMinValue); - - // Click the next button: We should now be waiting for center throttle in prep for inversion detection. - // Throttle channel is at minimum so Next button should be disabled. - NEXT_OR_CANCEL(1); - QCOMPARE(_calWidget->_rcCalState, PX4RCCalibration::rcCalStateCenterThrottle); - CHK_BUTTONS(cancelButtonMask); + _channelHomePosition(); - if (mode == testModeStandalone) { - _calWidget->_writeCalibration(false /* !trimsOnly */); - _validateParameters(validateMinMaxMask); - } -} - -void PX4RCCalibrationTest::_minMaxState_test(void) -{ - _minMaxState_worker(testModeStandalone); + int saveStep = _calWidget->_currentStep; + QTest::mouseClick(_nextButton, Qt::LeftButton); + QCOMPARE(_calWidget->_currentStep, saveStep + 1); } -void PX4RCCalibrationTest::_centerThrottleState_worker(enum TestMode mode) +void PX4RCCalibrationTest::_flapsDetectStep(void) { - bool tryCancel1 = true; + int channel = _rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionFlaps]; -StartOver: - if (mode == testModeStandalone || mode == testModePrerequisite) { - // In order to perform the center throttle state test the throttle channel has to have been identified. - // So we have to run the _identifyState_test first to set up the internal state correctly. - _identifyState_worker(testModePrerequisite); - - _centerChannels(); - _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionThrottle], (float)PX4RCCalibration::_rcCalPWMValidMinValue); - - _calWidget->_unitTestForceCalState(PX4RCCalibration::rcCalStateCenterThrottle); - - // We should now be waiting for center throttle in prep for inversion detection. - // Throttle channel is at minimum so Next button should be disabled. - CHK_BUTTONS(cancelButtonMask); - } - - // Move the throttle to just below rough center. Next should still be disabled - _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionThrottle], PX4RCCalibration::_rcCalPWMCenterPoint - PX4RCCalibration::_rcCalRoughCenterDelta - 1); - CHK_BUTTONS(cancelButtonMask); + //qDebug() << "_flapsDetectStep channel" << channel; - // Center the throttle and make sure Next button gets enabled - _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionThrottle], PX4RCCalibration::_rcCalPWMCenterPoint); - CHK_BUTTONS(cancelButtonMask | nextButtonMask); + // Test code can't handle reversed flaps channel + Q_ASSERT(!_rgChannelSettings[channel].reversed); - // Click the next button which should take us to our first channel inversion test. The Next button will stay disabled until - // the stick for the specified channel is moved down. - NEXT_OR_CANCEL(1); - QCOMPARE(_calWidget->_rcCalState, PX4RCCalibration::rcCalStateDetectInversion); - CHK_BUTTONS(cancelButtonMask); -} - -void PX4RCCalibrationTest::_centerThrottleState_test(void) -{ - _centerThrottleState_worker(testModeStandalone); -} - -void PX4RCCalibrationTest::_detectInversionState_worker(enum TestMode mode) -{ - bool tryCancel1 = true; - bool tryCancel2 = true; - -StartOver: - if (mode == testModeStandalone || mode == testModePrerequisite) { - // In order to perform the detect inversion test the roll/pitch/yaw/throttle functions must be mapped to a channel. - // So we have to run the _identifyState_test first to set up the internal state correctly. - _identifyState_worker(testModePrerequisite); - - _centerChannels(); - - _calWidget->_unitTestForceCalState(PX4RCCalibration::rcCalStateDetectInversion); - - // We should now be at the first channel inversion test. The Next button will stay disabled until the stick for the specified - // channel is moved in the appropriate direction. - CHK_BUTTONS(cancelButtonMask); - } + CHK_BUTTONS(nextButtonMask | cancelButtonMask | skipButtonMask); + + int saveStep = _calWidget->_currentStep; - // Loop over Attitude Control Functions (roll/yaw/pitch/throttle) to detect inversion - for (int chanFunction=PX4RCCalibration::rcCalFunctionFirstAttitudeFunction; chanFunction<=PX4RCCalibration::rcCalFunctionLastAttitudeFunction; chanFunction++) { - int channelIndex = _rgFunctionChannelMap[chanFunction]; - - if (chanFunction != 0) { - // Click next to move to next inversion to identify - NEXT_OR_CANCEL(1); - CHK_BUTTONS(cancelButtonMask); - } - - // Move all channels except for the one we are trying to detect to min and max value to make sure there is no effect. - for (int chan=0; chan<_availableChannels; chan++) { - if (channelIndex != chan) { - _mockUAS->emitRemoteControlChannelRawChanged(chan, (float)PX4RCCalibration::_rcCalPWMCenterPoint + (PX4RCCalibration::_rcCalMoveDelta + 2.0f)); - _mockUAS->emitRemoteControlChannelRawChanged(chan, (float)PX4RCCalibration::_rcCalPWMCenterPoint - (PX4RCCalibration::_rcCalMoveDelta + 2.0f)); - CHK_BUTTONS(cancelButtonMask); - - // Make sure to re-center for next inversion detect - //qDebug() << "Inversion recenter" << chan << PX4RCCalibration::_rcCalPWMCenterPoint; - _mockUAS->emitRemoteControlChannelRawChanged(chan, (float)PX4RCCalibration::_rcCalPWMCenterPoint); - } - } - - // Move the channel we are detecting inversion on to the min or max value depending onn test case data. - // This should put us in the found state and enable the Next button. - float inversionValue = PX4RCCalibration::_rcCalPWMCenterPoint; - float inversionDelta = (float)(PX4RCCalibration::_rcCalMoveDelta + 2.0f); - if (_rgChannelSettingsPreValidate[channelIndex].reversed) { - inversionValue += inversionDelta; - } else { - inversionValue -= inversionDelta; - } - //qDebug() << "Reverse set" << chanFunction << channelIndex << inversionValue; - _mockUAS->emitRemoteControlChannelRawChanged(channelIndex, inversionValue); - CHK_BUTTONS(cancelButtonMask | tryAgainButtonMask | nextButtonMask); - } + // Wiggle channel to identify + _stickMoveWaitForSettle(channel, _testMaxValue); + _stickMoveWaitForSettle(channel, _testMinValue); - // Click the next button: We should now be waiting for low throttle in prep for trim detection. - // Throttle channel is at minimum so Next button should be disabled. - _centerChannels(); - NEXT_OR_CANCEL(2); - QCOMPARE(_calWidget->_rcCalState, PX4RCCalibration::rcCalStateTrims); - CHK_BUTTONS(cancelButtonMask); + // Leave channel on full flaps down + _stickMoveWaitForSettle(channel, _testMaxValue); - if (mode == testModeStandalone) { - _calWidget->_writeCalibration(false /* !trimsOnly */); - _validateParameters(validateMappingMask | validateReversedMask); - } -} - -void PX4RCCalibrationTest::_detectInversionState_test(void) -{ - _detectInversionState_worker(testModeStandalone); + // User has to hit next at this step + QCOMPARE(_calWidget->_currentStep, saveStep); + CHK_BUTTONS(nextButtonMask | cancelButtonMask | skipButtonMask); + QTest::mouseClick(_nextButton, Qt::LeftButton); + QCOMPARE(_calWidget->_currentStep, saveStep + 1); } -void PX4RCCalibrationTest::_trimsState_worker(enum TestMode mode) +void PX4RCCalibrationTest::_switchSelectAutoStep(const char* functionStr, PX4RCCalibration::rcCalFunctions function) { - bool tryCancel1 = true; + Q_UNUSED(functionStr); + //qDebug() << "_switchSelectAutoStep" << functionStr << "function:" << function; -StartOver: - if (mode == testModeStandalone || mode == testModePrerequisite) { - // In order to perform the trim state test the functions must be mapped and the min/max values must be set. - // So we have to run the _minMaxState_test first to set up the internal state correctly. - _minMaxState_worker(testModePrerequisite); - - _centerChannels(); - - _calWidget->_unitTestForceCalState(PX4RCCalibration::rcCalStateTrims); - - // We should now be waiting for low throttle. - CHK_BUTTONS(cancelButtonMask); - } - - // Send trim values to channels - for (int chan=0; chan<_availableChannels; chan++) { - //qDebug () << "Trim set" << chan << _rgChannelSettingsPreValidate[chan].rcTrim; - _mockUAS->emitRemoteControlChannelRawChanged(chan, _rgChannelSettingsPreValidate[chan].rcTrim); + int buttonMask = cancelButtonMask; + if (function != PX4RCCalibration::rcCalFunctionModeSwitch) { + buttonMask |= skipButtonMask; } - _validateWidgets(validateTrimsMask, _rgChannelSettingsPreValidate); + CHK_BUTTONS(buttonMask); - // Throttle trim was set, so next should be enabled - CHK_BUTTONS(cancelButtonMask | nextButtonMask); + int saveStep = _calWidget->_currentStep; - // Click the next button which should set Trims and take us the Save step. - NEXT_OR_CANCEL(1); - QCOMPARE(_calWidget->_rcCalState, PX4RCCalibration::rcCalStateSave); - CHK_BUTTONS(cancelButtonMask | nextButtonMask); - _validateWidgets(validateTrimsMask, _rgChannelSettingsPostValidate); - - if (mode == testModeStandalone) { - _calWidget->_writeCalibration(false /* !trimsOnly */); - _validateParameters(validateTrimsMask); - } + // Wiggle stick for channel + int channel = _rgFunctionChannelMap[function]; + _mockUAS->emitRemoteControlChannelRawChanged(channel, _testMinValue); + _mockUAS->emitRemoteControlChannelRawChanged(channel, _testMaxValue); + + QCOMPARE(_calWidget->_currentStep, saveStep + 1); } -void PX4RCCalibrationTest::_trimsState_test(void) +void PX4RCCalibrationTest::_fullCalibration_test(void) { - _trimsState_worker(testModeStandalone); -} - -void PX4RCCalibrationTest::_fullCalibration_test(void) { - _centerChannels(); - QTest::mouseClick(_nextButton, Qt::LeftButton); - - _beginState_worker(testModeFullSequence); - _identifyState_worker(testModeFullSequence); - _minMaxState_worker(testModeFullSequence); - _centerThrottleState_worker(testModeFullSequence); - _detectInversionState_worker(testModeFullSequence); - _trimsState_worker(testModeFullSequence); + + _channelHomePosition(); + QTest::mouseClick(_nextButton, Qt::LeftButton); + _beginCalibration(); + _stickMoveAutoStep("Throttle", PX4RCCalibration::rcCalFunctionThrottle, moveToMax, true /* identify step */); + _stickMoveAutoStep("Throttle", PX4RCCalibration::rcCalFunctionThrottle, moveToMin, false /* not identify step */); + _stickMoveAutoStep("Yaw", PX4RCCalibration::rcCalFunctionYaw, moveToMax, true /* identify step */); + _stickMoveAutoStep("Yaw", PX4RCCalibration::rcCalFunctionYaw, moveToMin, false /* not identify step */); + _stickMoveAutoStep("Roll", PX4RCCalibration::rcCalFunctionRoll, moveToMax, true /* identify step */); + _stickMoveAutoStep("Roll", PX4RCCalibration::rcCalFunctionRoll, moveToMin, false /* not identify step */); + _stickMoveAutoStep("Pitch", PX4RCCalibration::rcCalFunctionPitch, moveToMax, true /* identify step */); + _stickMoveAutoStep("Pitch", PX4RCCalibration::rcCalFunctionPitch, moveToMin, false /* not identify step */); + _stickMoveAutoStep("Pitch", PX4RCCalibration::rcCalFunctionPitch, moveToCenter, false /* not identify step */); + _switchMinMaxStep(); + _flapsDetectStep(); + _stickMoveAutoStep("Flaps", PX4RCCalibration::rcCalFunctionFlaps, moveToMin, false /* not identify step */); + _switchSelectAutoStep("Mode", PX4RCCalibration::rcCalFunctionModeSwitch); + _switchSelectAutoStep("PostCtl", PX4RCCalibration::rcCalFunctionPosCtlSwitch); + _switchSelectAutoStep("Loiter", PX4RCCalibration::rcCalFunctionLoiterSwitch); + _switchSelectAutoStep("Return", PX4RCCalibration::rcCalFunctionReturnSwitch); + _switchSelectAutoStep("Aux1", PX4RCCalibration::rcCalFunctionAux1); + _switchSelectAutoStep("Aux2", PX4RCCalibration::rcCalFunctionAux2); // One more click and the parameters should get saved QTest::mouseClick(_nextButton, Qt::LeftButton); - - _validateParameters(validateAllMask); - _validateWidgets(validateAllMask, _rgChannelSettingsPostValidate); + _validateParameters(); } -/// @brief Sends RC center point values on minimum set of channels. -void PX4RCCalibrationTest::_centerChannels(void) +/// @brief Sets rc input to Throttle down home position. Centers all other channels. +void PX4RCCalibrationTest::_channelHomePosition(void) { - // Initialize available channels them to center point. This should also set the channel count above the - // minimum such that we can enter the idle state. + // Initialize available channels to center point. for (int i=0; i<_availableChannels; i++) { _mockUAS->emitRemoteControlChannelRawChanged(i, (float)PX4RCCalibration::_rcCalPWMCenterPoint); } + + // Throttle to low position (throttle is not reversed)/ + _mockUAS->emitRemoteControlChannelRawChanged(_rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionThrottle], _testMinValue); } -void PX4RCCalibrationTest::_validateParameters(int validateMask) +void PX4RCCalibrationTest::_validateParameters(void) { MockQGCUASParamManager* paramMgr = _mockUAS->getMockQGCUASParamManager(); MockQGCUASParamManager::ParamMap_t mapParamsSet = paramMgr->getMockSetParameters(); @@ -604,104 +452,67 @@ void PX4RCCalibrationTest::_validateParameters(int validateMask) QString trimTpl("RC%1_TRIM"); QString revTpl("RC%1_REV"); - if (validateMask & validateMappingMask) { - // Check mapping for all fuctions - for (int chanFunction=0; chanFunctionisMinMaxShown(), rgChannelSettings[chan].isMinMaxShown); - QCOMPARE(radioWidget->min(), rgChannelSettings[chan].rcMin); - QCOMPARE(radioWidget->max(), rgChannelSettings[chan].rcMax); - QCOMPARE(radioWidget->isMinValid(), rgChannelSettings[chan].isMinValid); - QCOMPARE(radioWidget->isMaxValid(), rgChannelSettings[chan].isMaxValid); - } - - if (validateMask & validateTrimsMask) { - //qDebug() << "Trim validate widget" << chan; - QCOMPARE(radioWidget->trim(), rgChannelSettings[chan].rcTrim); + int expectedValue; + if (_rgFunctionChannelMap[chanFunction] == -1) { + expectedValue = 0; // 0 signals no mapping + } else { + expectedValue = _rgFunctionChannelMap[chanFunction] + 1; // 1-based } + // qDebug() << chanFunction << expectedValue << mapParamsSet[PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName].toInt(); + QCOMPARE(mapParamsSet[PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName].toInt(), expectedValue); } - - for (int chan=_availableChannels; chanisEnabled(), false); - } -} \ No newline at end of file +} diff --git a/src/qgcunittest/PX4RCCalibrationTest.h b/src/qgcunittest/PX4RCCalibrationTest.h index 94b39a826005355b0b8e36b2611c6d816991405c..a48a10d28387b6fde634c010b4d582f4628a4c3e 100644 --- a/src/qgcunittest/PX4RCCalibrationTest.h +++ b/src/qgcunittest/PX4RCCalibrationTest.h @@ -27,6 +27,7 @@ #include "AutoTest.h" #include "MockUASManager.h" #include "MockUAS.h" +#include "MultiSignalSpy.h" #include "px4_configuration/PX4RCCalibration.h" /// @file @@ -49,13 +50,6 @@ private slots: void _setUAS_test(void); void _minRCChannels_test(void); - //void _liveRC_test(void); - void _beginState_test(void); - void _identifyState_test(void); - void _minMaxState_test(void); - void _centerThrottleState_test(void); - void _detectInversionState_test(void); - void _trimsState_test(void); void _fullCalibration_test(void); private: @@ -66,13 +60,20 @@ private: testModeFullSequence, ///< Run as full calibration sequence }; - void _centerChannels(void); - void _beginState_worker(enum TestMode mode); - void _identifyState_worker(enum TestMode mode); - void _minMaxState_worker(enum TestMode mode); - void _centerThrottleState_worker(enum TestMode mode); - void _detectInversionState_worker(enum TestMode mode); - void _trimsState_worker(enum TestMode mode); + enum MoveToDirection { + moveToMax, + moveToMin, + moveToCenter, + }; + + void _channelHomePosition(void); + void _minRCChannels(void); + void _beginCalibration(void); + void _stickMoveWaitForSettle(int channel, int value); + void _stickMoveAutoStep(const char* functionStr, enum PX4RCCalibration::rcCalFunctions function, enum MoveToDirection direction, bool identifyStep); + void _switchMinMaxStep(void); + void _flapsDetectStep(void); + void _switchSelectAutoStep(const char* functionStr, PX4RCCalibration::rcCalFunctions function); enum { validateMinMaxMask = 1 << 0, @@ -88,13 +89,9 @@ private: int rcMax; int rcTrim; int reversed; - bool isMinMaxShown; - bool isMinValid; - bool isMaxValid; }; - void _validateParameters(int validateMask); - void _validateWidgets(int validateMask, const struct ChannelSettings* rgChannelSettings); + void _validateParameters(void); MockUASManager* _mockUASManager; MockUAS* _mockUAS; @@ -104,29 +101,30 @@ private: enum { nextButtonMask = 1 << 0, cancelButtonMask = 1 << 1, - skipButtonMask = 1 << 2, - tryAgainButtonMask = 1 << 3 + skipButtonMask = 1 << 2 }; QPushButton* _nextButton; QPushButton* _cancelButton; QPushButton* _skipButton; - QPushButton* _tryAgainButton; QLabel* _statusLabel; - RCChannelWidget* _rgRadioWidget[PX4RCCalibration::_chanMax]; + RCValueWidget* _rgValueWidget[PX4RCCalibration::_chanMax]; + + const char* _rgSignals[1]; + MultiSignalSpy* _multiSpyNextButtonMessageBox; // When settings values into min/max/trim we set them slightly different than the defaults so that // we can distinguish between the two values. static const int _testMinValue; static const int _testMaxValue; - static const int _testTrimValue; - static const int _testThrottleTrimValue; + static const int _testCenterValue; static const int _availableChannels = 18; ///< Simulate 18 channel RC Transmitter + static const int _stickSettleWait; - static const struct ChannelSettings _rgChannelSettingsPreValidate[_availableChannels]; - static const struct ChannelSettings _rgChannelSettingsPostValidate[PX4RCCalibration::_chanMax]; + static const struct ChannelSettings _rgChannelSettings[_availableChannels]; + static const struct ChannelSettings _rgChannelSettingsValidate[PX4RCCalibration::_chanMax]; static const int _rgFunctionChannelMap[PX4RCCalibration::rcCalFunctionMax]; }; diff --git a/src/ui/QGCPX4VehicleConfig.ui b/src/ui/QGCPX4VehicleConfig.ui index 8d3c5599318f710f5f5de80f185833e32b1fb5d3..e49b37c0d4a76a80f97c7d33c15b67f78533d3d1 100644 --- a/src/ui/QGCPX4VehicleConfig.ui +++ b/src/ui/QGCPX4VehicleConfig.ui @@ -94,14 +94,14 @@ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'.Lucida Grande UI'; font-size:16pt; font-weight:600; font-style:normal;"> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt; font-weight:400;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt; font-weight:400;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt; font-weight:400;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt; font-weight:400;"><br /></p> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:24pt; font-weight:400;">Coming Soon</span></p> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:24pt; font-weight:400;">(Use Advanced Config instead)</span></p></body></html> +</style></head><body style=" font-family:'.Helvetica Neue DeskInterface'; font-size:16pt; font-weight:600; font-style:normal;"> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI';"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt; font-weight:400;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt; font-weight:400;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt; font-weight:400;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt; font-weight:400;"><br /></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'.Lucida Grande UI'; font-size:24pt; font-weight:400;">Coming Soon</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'.Lucida Grande UI'; font-size:24pt; font-weight:400;">(Use Advanced Config instead)</span></p></body></html> @@ -145,8 +145,8 @@ p, li { white-space: pre-wrap; } 0 0 - 592 - 1017 + 16 + 16 @@ -266,14 +266,14 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'.Lucida Grande UI'; font-size:13pt; font-weight:400; font-style:normal;"> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:24pt;">Coming Soon</span></p> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:24pt;">(Use Radio Calibration instead)</span></p></body></html> +</style></head><body style=" font-family:'.Helvetica Neue DeskInterface'; font-size:13pt; font-weight:400; font-style:normal;"> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI';"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'.Lucida Grande UI'; font-size:24pt;">Coming Soon</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'.Lucida Grande UI'; font-size:24pt;">(Use Radio Calibration instead)</span></p></body></html> @@ -287,14 +287,14 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'.Lucida Grande UI'; font-size:13pt; font-weight:400; font-style:normal;"> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:24pt;"><br /></p> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:24pt;">Coming Soon</span></p> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:24pt;">(Use Advanced Config instead)</span></p></body></html> +</style></head><body style=" font-family:'.Helvetica Neue DeskInterface'; font-size:13pt; font-weight:400; font-style:normal;"> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI';"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'.Lucida Grande UI'; font-size:24pt;"><br /></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'.Lucida Grande UI'; font-size:24pt;">Coming Soon</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'.Lucida Grande UI'; font-size:24pt;">(Use Advanced Config instead)</span></p></body></html> diff --git a/src/ui/px4_configuration/PX4RCCalibration.cc b/src/ui/px4_configuration/PX4RCCalibration.cc index efdab85ed97e25ecddf049f6320d1352fcbaab46..980de59837c51ced3fbd69b1e5b22f91a8157acb 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.cc +++ b/src/ui/px4_configuration/PX4RCCalibration.cc @@ -21,7 +21,6 @@ ======================================================================*/ - /// @file /// @brief PX4 RC Calibration Widget /// @author Don Gagne setupUi(this); - // Initialize arrays of widget control pointers. This allows for more efficient code writing using "for" loops. + // Initialize arrays of monitor control pointers. This allows for more efficient code writing using "for" loops. for (int chan=0; chan<_chanMax; chan++) { - QString radioWidgetName("radio%1Widget"); - QString radioWidgetUserName("Channel %1"); + QString radioWidgetName; - RCChannelWidget* radioWidget = findChild(radioWidgetName.arg(chan+1)); - Q_ASSERT(radioWidget); + radioWidgetName = "channel%1Value"; + RCValueWidget* monitorWidget = findChild(radioWidgetName.arg(chan+1)); + Q_ASSERT(monitorWidget); + _rgRCValueMonitorWidget[chan] = monitorWidget; + monitorWidget->setSmallMode(); // Monitor display uses small display - radioWidget->setTitle(radioWidgetUserName.arg(chan+1)); - - _rgRadioWidget[chan] = radioWidget; + radioWidgetName = "channel%1Label"; + QLabel* monitorLabel = findChild(radioWidgetName.arg(chan+1)); + Q_ASSERT(monitorLabel); + _rgRCValueMonitorLabel[chan] = monitorLabel; } + + // Initialize array of attitude controls. Order here doesn't matter. + _rgAttitudeControl[0].function = rcCalFunctionThrottle; + _rgAttitudeControl[0].valueWidget = _ui->throttleValue; + _rgAttitudeControl[1].function = rcCalFunctionYaw; + _rgAttitudeControl[1].valueWidget = _ui->yawValue; + _rgAttitudeControl[2].function = rcCalFunctionRoll; + _rgAttitudeControl[2].valueWidget = _ui->rollValue; + _rgAttitudeControl[3].function = rcCalFunctionPitch; + _rgAttitudeControl[3].valueWidget = _ui->pitchValue; + _rgAttitudeControl[4].function = rcCalFunctionFlaps; + _rgAttitudeControl[4].valueWidget = _ui->flapsValue; _setActiveUAS(UASManager::instance()->getActiveUAS()); @@ -90,27 +121,529 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) : fSucceeded = connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(_setActiveUAS(UASInterface*))); Q_ASSERT(fSucceeded); - fSucceeded = connect(_ui->spektrumPairButton, SIGNAL(clicked(bool)), this, SLOT(_toggleSpektrumPairing(bool))); - Q_ASSERT(fSucceeded); + connect(_ui->spektrumBind, &QPushButton::clicked, this, &PX4RCCalibration::_spektrumBind); _updateTimer.setInterval(150); _updateTimer.start(); - fSucceeded = connect(&_updateTimer, SIGNAL(timeout()), this, SLOT(_updateView())); - Q_ASSERT(fSucceeded); + connect(&_updateTimer, &QTimer::timeout, this, &PX4RCCalibration::_updateView); - fSucceeded= connect(_ui->rcCalCancel, SIGNAL(clicked(void)), this, SLOT(_rcCalCancel(void))); - Q_ASSERT(fSucceeded); + connect(_ui->rcCalCancel, &QPushButton::clicked, this, &PX4RCCalibration::_stopCalibration); + connect(_ui->rcCalSkip, &QPushButton::clicked, this, &PX4RCCalibration::_skipButton); + connect(_ui->rcCalNext, &QPushButton::clicked, this, &PX4RCCalibration::_nextButton); + + connect(_ui->rollTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); + connect(_ui->yawTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); + connect(_ui->pitchTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); + connect(_ui->throttleTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); + + _stopCalibration(); +} - fSucceeded= connect(_ui->rcCalSkip, SIGNAL(clicked(void)), this, SLOT(_rcCalSkip(void))); - Q_ASSERT(fSucceeded); +PX4RCCalibration::~PX4RCCalibration() +{ +} - fSucceeded= connect(_ui->rcCalTryAgain, SIGNAL(clicked(void)), this, SLOT(_rcCalTryAgain(void))); - Q_ASSERT(fSucceeded); +/// @brief Returns the state machine entry for the specified state. +const PX4RCCalibration::stateMachineEntry* PX4RCCalibration::_getStateMachineEntry(int step) +{ + static const char* msgBegin = "Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\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* msgThrottleUp = "Move the Throttle stick all the way up and hold it there..."; + static const char* msgThrottleDown = "Move the Throttle stick all the way down and leave it there..."; + static const char* msgYawLeft = "Move the Yaw stick all the way to the left and hold it there..."; + static const char* msgYawRight = "Move the Yaw stick all the way to the right and hold it there..."; + static const char* msgRollLeft = "Move the Roll stick all the way to the left and hold it there..."; + static const char* msgRollRight = "Move the Roll stick all the way to the right and hold it there..."; + static const char* msgPitchDown = "Move the Pitch stick all the way down and hold it there..."; + static const char* msgPitchUp = "Move the Pitch stick all the way up and hold it there..."; + static const char* msgPitchCenter = "Allow the Pitch stick to move back to center..."; + static const char* msgModeSwitch = "Next we will assign the channel for the Mode Switch. Move the switch or dial up and down to select the channel."; + static const char* msgPosCtlSwitch = "Next we will assign the channel for the PosCtl Switch. Move the switch or dial up and down to select the channel.\n\n" + "You can click Skip if you don't want to assign this switch."; + static const char* msgLoiterSwitch = "Next we will assign the channel for the Loiter Switch. Move the switch or dial up and down to select the channel.\n\n" + "You can click Skip if you don't want to assign this switch."; + static const char* msgReturnSwitch = "Next we will assign the channel for the Return Switch. Move the switch or dial up and down to select the channel.\n\n" + "You can click Skip if you don't want to assign this switch."; + static const char* msgAux1Switch = "Move the switch or dial you want to use for Aux1.\n\n" + "You can click Skip if you don't want to assign."; + static const char* msgAux2Switch = "Move the switch or dial you want to use for Aux2.\n\n" + "You can click Skip if you don't want to assign."; + static const char* msgSwitchMinMax = "Move all the transmitter switches and/or dials back and forth to their extreme positions."; + static const char* msgFlapsDetect = "Move the switch or dial you want to use for Flaps back and forth a few times. " + "Then leave the switch/dial at the position you want to use for Flaps fully extended.\n\n" + "Click Next to continue.\n" + "If you won't be using Flaps, click Skip."; + static const char* msgFlapsUp = "Move the switch or dial you want to use for Flaps to the position you want to use for Flaps fully retracted."; + static const char* msgComplete = "All settings have been captured. Click Next to write the new parameters to your board."; + + static const stateMachineEntry rgStateMachine[] = { + //Function + { rcCalFunctionMax, msgBegin, _imageHome, &PX4RCCalibration::_inputCenterWaitBegin, &PX4RCCalibration::_saveAllTrims, NULL }, + { rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, + { rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &PX4RCCalibration::_inputStickMin, NULL, NULL }, + { rcCalFunctionYaw, msgYawRight, _imageYawRight, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, + { rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &PX4RCCalibration::_inputStickMin, NULL, NULL }, + { rcCalFunctionRoll, msgRollRight, _imageRollRight, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, + { rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &PX4RCCalibration::_inputStickMin, NULL, NULL }, + { rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, + { rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &PX4RCCalibration::_inputStickMin, NULL, NULL }, + { rcCalFunctionPitch, msgPitchCenter, _imageHome, &PX4RCCalibration::_inputCenterWait, NULL, NULL }, + { rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &PX4RCCalibration::_inputSwitchMinMax, &PX4RCCalibration::_nextStep, NULL }, + { rcCalFunctionFlaps, msgFlapsDetect, _imageThrottleDown, &PX4RCCalibration::_inputFlapsDetect, &PX4RCCalibration::_saveFlapsDown, &PX4RCCalibration::_skipFlaps }, + { rcCalFunctionFlaps, msgFlapsUp, _imageThrottleDown, &PX4RCCalibration::_inputFlapsUp, NULL, NULL }, + { rcCalFunctionModeSwitch, msgModeSwitch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, NULL }, + { rcCalFunctionPosCtlSwitch, msgPosCtlSwitch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, + { rcCalFunctionLoiterSwitch, msgLoiterSwitch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, + { rcCalFunctionReturnSwitch, msgReturnSwitch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, + { rcCalFunctionAux1, msgAux1Switch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, + { rcCalFunctionAux2, msgAux2Switch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, + { rcCalFunctionMax, msgComplete, _imageThrottleDown, NULL, &PX4RCCalibration::_writeCalibration, NULL }, + }; + + Q_ASSERT(step >=0 && step < (int)(sizeof(rgStateMachine) / sizeof(rgStateMachine[0]))); + + return &rgStateMachine[step]; +} - fSucceeded= connect(_ui->rcCalNext, SIGNAL(clicked(void)), this, SLOT(_rcCalNext(void))); - Q_ASSERT(fSucceeded); +void PX4RCCalibration::_nextStep(void) +{ + _currentStep++; + _setupCurrentState(); +} + + +/// @brief Sets up the state machine according to the current step from _currentStep. +void PX4RCCalibration::_setupCurrentState(void) +{ + const stateMachineEntry* state = _getStateMachineEntry(_currentStep); + + _ui->rcCalStatus->setText(state->instructions); + _ui->radioIcon->setPixmap(QPixmap(QString(_imageFilePrefix) + state->image)); + + _stickDetectChannel = _chanMax; + _stickDetectSettleStarted = false; + + _rcCalSaveCurrentValues(); + + _ui->rcCalNext->setEnabled(state->nextFn != NULL); + _ui->rcCalSkip->setEnabled(state->skipFn != NULL); +} + +/// @brief This routine is called whenever a raw value for an RC channel changes. It will call the input +/// function as specified by the state machine. +/// @param chan RC channel on which signal is coming from (0-based) +/// @param fval Current value for channel +void PX4RCCalibration::_remoteControlChannelRawChanged(int chan, float fval) +{ + Q_ASSERT(chan >= 0 && chan <= _chanMax); + + // We always update raw values + _rcRawValue[chan] = fval; + + //qDebug() << "Raw value" << chan << fval; + + if (_currentStep == -1) { + // Track the receiver channel count by keeping track of how many channels we see + if (chan + 1 > (int)_chanCount) { + _chanCount = chan + 1; + _ui->receiverInfo->setText(tr("%1 channel receiver").arg(_chanCount)); + if (_chanCount < _chanMinimum) { + _ui->rcCalStatus->setText(tr("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); + } else { + _ui->rcCalStatus->clear(); + } + } + } + + if (_currentStep != -1) { + const stateMachineEntry* state = _getStateMachineEntry(_currentStep); + Q_ASSERT(state); + if (state->rcInputFn) { + (this->*state->rcInputFn)(state->function, chan, fval); + } + } +} + +void PX4RCCalibration::_nextButton(void) +{ + if (_currentStep == -1) { + // Need to have enough channels + if (_chanCount < _chanMinimum) { + if (_unitTestMode) { + emit nextButtonMessageBoxDisplayed(); + } else { + QMessageBox::warning(this, tr("Receiver"), tr("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); + Q_ASSERT(state); + Q_ASSERT(state->nextFn); + (this->*state->nextFn)(); + } +} + +void PX4RCCalibration::_skipButton(void) +{ + Q_ASSERT(_currentStep != -1); + + const stateMachineEntry* state = _getStateMachineEntry(_currentStep); + Q_ASSERT(state); + Q_ASSERT(state->skipFn); + (this->*state->skipFn)(); +} + +void PX4RCCalibration::_trimNYI(void) +{ + QMessageBox::warning(this, tr("Set Trim"), tr("Setting individual trims is not yet implemented. You will need to go through full calibration to set trims.")); +} + +void PX4RCCalibration::_saveAllTrims(void) +{ + // 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 + // channels they are yet. AS we continue through the process the other channels will get their + // trims reset to correct values. + + for (int i=0; i<_chanCount; i++) { + //qDebug() << "_saveAllTrims trim" << _rcRawValue[i]; + _rgChannelInfo[i].rcTrim = _rcRawValue[i]; + } + _nextStep(); +} + +/// @brief Waits for the sticks to be centered, enabling Next when done. +void PX4RCCalibration::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value) +{ + Q_UNUSED(function); + Q_UNUSED(chan); + Q_UNUSED(value); + + // FIXME: Doesn't wait for center + + _ui->rcCalNext->setEnabled(true); +} + +bool PX4RCCalibration::_stickSettleComplete(int value) +{ + // We are waiting for the stick to settle out to a max position + + if (abs(_stickDetectValue - value) > _rcCalSettleDelta) { + // Stick is moving too much to consider stopped + + //qDebug() << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value; + + _stickDetectValue = value; + _stickDetectSettleStarted = false; + } else { + // Stick is still positioned within the specified small range + + if (_stickDetectSettleStarted) { + // We have already started waiting + + if (_stickDetectSettleElapsed.elapsed() > _stickDetectSettleMSecs) { + // Stick has stayed positioned in one place long enough, detection is complete. + return true; + } + } else { + // Start waiting for the stick to stay settled for _stickDetectSettleWaitMSecs msecs + + //qDebug() << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value; + + _stickDetectSettleStarted = true; + _stickDetectSettleElapsed.start(); + } + } + + return false; +} + +void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int channel, int value) +{ + //qDebug() << "_inputStickDetect function:channel:value" << function << channel << value; + + // If this channel is already used in a mapping we can't use it again + if (_rgChannelInfo[channel].function != rcCalFunctionMax) { + return; + } - _rcCalChannelWait(true); + if (_stickDetectChannel == _chanMax) { + // We have not detected enough movement on a channel yet + + if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) { + // Stick has moved far enough to consider it as being selected for the function + + //qDebug() << "_inputStickDetect starting settle wait, function:channel:value" << function << channel << value; + + // Setup up to detect stick being pegged to min or max value + _stickDetectChannel = channel; + _stickDetectInitialValue = value; + _stickDetectValue = value; + } + } else if (channel == _stickDetectChannel) { + if (_stickSettleComplete(value)) { + ChannelInfo* info = &_rgChannelInfo[channel]; + + //qDebug() << "_inputStickDetect settle complete, function:channel:value" << function << channel << value; + + // Stick detection is complete. Stick should be at max position. + // Map the channel to the function + _rgFunctionChannelMapping[function] = channel; + info->function = function; + + // Channel should be at max value, if it is below initial set point the the channel is reversed. + info->reversed = value < _rcValueSave[channel]; + + if (info->reversed) { + _rgRCValueMonitorWidget[channel]->setMin(value); + _rgRCValueMonitorWidget[channel]->setMinValid(true); + _rgChannelInfo[channel].rcMin = value; + } else { + _rgRCValueMonitorWidget[channel]->setMax(value); + _rgRCValueMonitorWidget[channel]->setMaxValid(true); + _rgChannelInfo[channel].rcMax = value; + } + + _nextStep(); + } + } +} + +void PX4RCCalibration::_inputStickMin(enum 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; + } + + if (_stickDetectChannel == _chanMax) { + // Setup up to detect stick being pegged to extreme position + if (_rgChannelInfo[channel].reversed) { + if (value > _rcCalPWMCenterPoint + _rcCalMoveDelta) { + _stickDetectChannel = channel; + _stickDetectInitialValue = value; + _stickDetectValue = value; + } + } else { + if (value < _rcCalPWMCenterPoint - _rcCalMoveDelta) { + _stickDetectChannel = channel; + _stickDetectInitialValue = value; + _stickDetectValue = value; + } + } + } else { + // We are waiting for the selected channel to settle out + + if (_stickSettleComplete(value)) { + ChannelInfo* info = &_rgChannelInfo[channel]; + + // Stick detection is complete. Stick should be at min position. + if (info->reversed) { + _rgRCValueMonitorWidget[channel]->setMax(value); + _rgRCValueMonitorWidget[channel]->setMaxValid(true); + _rgChannelInfo[channel].rcMax = value; + } else { + _rgRCValueMonitorWidget[channel]->setMin(value); + _rgRCValueMonitorWidget[channel]->setMinValid(true); + _rgChannelInfo[channel].rcMin = value; + } + + _nextStep(); + } + } +} + +void PX4RCCalibration::_inputCenterWait(enum 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; + } + + if (_stickDetectChannel == _chanMax) { + // Sticks have not yet moved close enough to center + + if (abs(_rcCalPWMCenterPoint - value) < _rcCalRoughCenterDelta) { + // Stick has moved close enough to center that we can start waiting for it to settle + _stickDetectChannel = channel; + _stickDetectInitialValue = value; + _stickDetectValue = value; + } + } else { + if (_stickSettleComplete(value)) { + _nextStep(); + } + } +} + +/// @brief Saves min/max for non-mapped channels +void PX4RCCalibration::_inputSwitchMinMax(enum rcCalFunctions function, int channel, int value) +{ + Q_UNUSED(function); + + // If the channel is mapped we already have min/max + if (_rgChannelInfo[channel].function != rcCalFunctionMax) { + return; + } + + 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); + + //qDebug() << "_inputSwitchMinMax setting min channel:min" << channel << minValue; + + _rgChannelInfo[channel].rcMin = minValue; + _rgRCValueMonitorWidget[channel]->setMin(minValue); + _rgRCValueMonitorWidget[channel]->setMinValid(true); + } else { + int maxValue = qMax(_rgChannelInfo[channel].rcMax, value); + + //qDebug() << "_inputSwitchMinMax setting max channel:max" << channel << maxValue; + + _rgChannelInfo[channel].rcMax = maxValue; + _rgRCValueMonitorWidget[channel]->setMax(maxValue); + _rgRCValueMonitorWidget[channel]->setMaxValid(true); + } + } +} + +void PX4RCCalibration::_skipFlaps(void) +{ + // Flaps channel may have been identified. Clear it out. + for (int i=0; i<_chanCount; i++) { + if (_rgChannelInfo[i].function == PX4RCCalibration::rcCalFunctionFlaps) { + _rgChannelInfo[i].function = rcCalFunctionMax; + } + } + _rgFunctionChannelMapping[PX4RCCalibration::rcCalFunctionFlaps] = _chanMax; + + // Skip over flap steps + _currentStep += 2; + _setupCurrentState(); +} + +void PX4RCCalibration::_saveFlapsDown(void) +{ + int channel = _rgFunctionChannelMapping[rcCalFunctionFlaps]; + + if (channel == _chanMax) { + // Channel not yet mapped, still waiting for switch to move + if (_unitTestMode) { + emit nextButtonMessageBoxDisplayed(); + } else { + QMessageBox::warning(this, tr("Flaps switch"), tr("Flaps switch has not yet been detected.")); + } + return; + } + + Q_ASSERT(channel != -1); + ChannelInfo* info = &_rgChannelInfo[channel]; + + int rcValue = _rcRawValue[channel]; + + // Switch detection is complete. Switch should be at flaps fully extended position. + + // Channel should be at max value, if it is below initial set point the channel is reversed. + info->reversed = rcValue < _rcValueSave[channel]; + + if (info->reversed) { + _rgRCValueMonitorWidget[channel]->setMin(rcValue); + _rgRCValueMonitorWidget[channel]->setMinValid(true); + _rgChannelInfo[channel].rcMin = rcValue; + } else { + _rgRCValueMonitorWidget[channel]->setMax(rcValue); + _rgRCValueMonitorWidget[channel]->setMaxValid(true); + _rgChannelInfo[channel].rcMax = rcValue; + } + + _nextStep(); +} + +void PX4RCCalibration::_inputFlapsUp(enum rcCalFunctions function, int channel, int value) +{ + // FIXME: Duplication + + Q_ASSERT(function == rcCalFunctionFlaps); + + // We only care about the channel mapped to flaps + if (_rgFunctionChannelMapping[rcCalFunctionFlaps] != channel) { + return; + } + + if (_stickDetectChannel == _chanMax) { + // Setup up to detect stick being pegged to extreme position + if (_rgChannelInfo[channel].reversed) { + if (value > _rcCalPWMCenterPoint + _rcCalMoveDelta) { + _stickDetectChannel = channel; + _stickDetectInitialValue = value; + _stickDetectValue = value; + } + } else { + if (value < _rcCalPWMCenterPoint - _rcCalMoveDelta) { + _stickDetectChannel = channel; + _stickDetectInitialValue = value; + _stickDetectValue = value; + } + } + } else { + // We are waiting for the selected channel to settle out + + if (_stickSettleComplete(value)) { + ChannelInfo* info = &_rgChannelInfo[channel]; + + // Stick detection is complete. Stick should be at min position. + if (info->reversed) { + _rgRCValueMonitorWidget[channel]->setMax(value); + _rgRCValueMonitorWidget[channel]->setMaxValid(true); + _rgChannelInfo[channel].rcMax = value; + } else { + _rgRCValueMonitorWidget[channel]->setMin(value); + _rgRCValueMonitorWidget[channel]->setMinValid(true); + _rgChannelInfo[channel].rcMin = value; + } + + _nextStep(); + } + } +} + +void PX4RCCalibration::_switchDetect(enum 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) { + return; + } + + if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) { + ChannelInfo* info = &_rgChannelInfo[channel]; + + // Switch has moved far enough to consider it as being selected for the function + + // Map the channel to the function + _rgChannelInfo[channel].function = function; + _rgFunctionChannelMapping[function] = channel; + info->function = function; + + //qDebug() << "Function:" << function << "mapped to:" << channel; + + if (moveToNextStep) { + _nextStep(); + } + } +} + +void PX4RCCalibration::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value) +{ + _switchDetect(function, channel, value, true /* move to next step after detection */); +} + +void PX4RCCalibration::_inputFlapsDetect(enum rcCalFunctions function, int channel, int value) +{ + _switchDetect(function, channel, value, false /* do not move to next step after detection */); } /// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence. @@ -135,7 +668,7 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void) _showTrimOnRadioWidgets(false); } -/// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence. +/// @brief Sets internal calibration values from the stored parameters void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) { Q_ASSERT(_paramMgr); @@ -221,32 +754,34 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) } /// @brief Sets a connected Spektrum receiver into bind mode -void PX4RCCalibration::_toggleSpektrumPairing(bool enabled) -{ - Q_UNUSED(enabled); - - if (!_ui->dsm2RadioButton->isChecked() && !_ui->dsmxRadioButton->isChecked() - && !_ui->dsmx8RadioButton->isChecked()) { - // Reject - QMessageBox warnMsgBox; - warnMsgBox.setText(tr("Please select a Spektrum Protocol Version")); - warnMsgBox.setInformativeText(tr("Please select either DSM2 or DSM-X\ndirectly below the pair button,\nbased on the receiver type.")); - warnMsgBox.setStandardButtons(QMessageBox::Ok); - warnMsgBox.setDefaultButton(QMessageBox::Ok); - (void)warnMsgBox.exec(); - return; - } +void PX4RCCalibration::_spektrumBind(void) +{ + + Q_ASSERT(_mav); - UASInterface* mav = UASManager::instance()->getActiveUAS(); - if (mav) { - int rxSubType; - if (_ui->dsm2RadioButton->isChecked()) - rxSubType = 0; - else if (_ui->dsmxRadioButton->isChecked()) - rxSubType = 1; - else // if (_ui->dsmx8RadioButton->isChecked()) - rxSubType = 2; - mav->pairRX(0, rxSubType); + QMessageBox bindTypeMsg(this); + + bindTypeMsg.setWindowModality(Qt::ApplicationModal); + QPushButton* dsm2Mode = bindTypeMsg.addButton("DSM2", QMessageBox::AcceptRole); + QPushButton* dsmx7Mode = bindTypeMsg.addButton("DSMX (7 channels or less)", QMessageBox::AcceptRole); + QPushButton* dsmx8Mode = bindTypeMsg.addButton("DSMX (8 channels or more)", QMessageBox::AcceptRole); + bindTypeMsg.addButton(QMessageBox::Cancel); + + bindTypeMsg.setWindowTitle(tr("Spektrum Bind")); + bindTypeMsg.setText(tr("Place Spektrum satellite receiver in bind mode. Select which mode below.")); + + int bindType; + if (bindTypeMsg.exec() != QMessageBox::Cancel) { + if (bindTypeMsg.clickedButton() == dsm2Mode) { + bindType = 0; + } else if (bindTypeMsg.clickedButton() == dsmx7Mode) { + bindType = 1; + } else if (bindTypeMsg.clickedButton() == dsmx8Mode) { + bindType = 2; + } else { + Q_ASSERT(false); + } + _mav->pairRX(0, bindType); } } @@ -288,15 +823,30 @@ void PX4RCCalibration::_validateCalibration(void) // Validate Min/Max values. Although the channel appears as available we still may // not have good min/max/trim values for it. Set to defaults if needed. if (info->rcMin > _rcCalPWMValidMinValue || info->rcMax < _rcCalPWMValidMaxValue) { + //qDebug() << "_validateCalibration resetting channel" << chan; info->rcMin = _rcCalPWMDefaultMinValue; info->rcMax = _rcCalPWMDefaultMaxValue; - info->rcTrim = _rcCalPWMDefaultTrimValue; + info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); + } else { + switch (_rgChannelInfo[chan].function) { + case rcCalFunctionThrottle: + case rcCalFunctionYaw: + case rcCalFunctionRoll: + case rcCalFunctionPitch: + break; + default: + // Non-attitude control channels have calculated trim + info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); + break; + } + } } else { // Unavailable channels are set to defaults + //qDebug() << "_validateCalibration resetting unavailable channel" << chan; info->rcMin = _rcCalPWMDefaultMinValue; info->rcMax = _rcCalPWMDefaultMaxValue; - info->rcTrim = _rcCalPWMDefaultTrimValue; + info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); info->reversed = false; } } @@ -305,7 +855,7 @@ void PX4RCCalibration::_validateCalibration(void) /// @brief Saves the rc calibration values to the board parameters. /// @param trimsOnly true: write only trim values, false: write all calibration values -void PX4RCCalibration::_writeCalibration(bool trimsOnly) +void PX4RCCalibration::_writeCalibration(void) { if (!_mav) return; @@ -321,464 +871,117 @@ void PX4RCCalibration::_writeCalibration(bool trimsOnly) QString trimTpl("RC%1_TRIM"); QString revTpl("RC%1_REV"); + // 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; - paramMgr->setPendingParam(0, trimTpl.arg(oneBasedChannel), info->rcTrim); - if (!trimsOnly) { - paramMgr->setPendingParam(0, minTpl.arg(oneBasedChannel), info->rcMin); - paramMgr->setPendingParam(0, maxTpl.arg(oneBasedChannel), info->rcMax); - paramMgr->setPendingParam(0, revTpl.arg(oneBasedChannel), info->reversed ? -1.0f : 1.0f); - } + paramMgr->setPendingParam(0, trimTpl.arg(oneBasedChannel), (float)info->rcTrim); + paramMgr->setPendingParam(0, minTpl.arg(oneBasedChannel), (float)info->rcMin); + paramMgr->setPendingParam(0, maxTpl.arg(oneBasedChannel), (float)info->rcMax); + paramMgr->setPendingParam(0, revTpl.arg(oneBasedChannel), info->reversed ? -1.0f : 1.0f); } - if (!trimsOnly) { - // Write function mapping parameters - for (size_t i=0; isetPendingParam(0, _rgFunctionInfo[i].parameterName, paramChannel); + // Write function mapping parameters + for (size_t i=0; isetPendingParam(0, _rgFunctionInfo[i].parameterName, paramChannel); } //let the param mgr manage sending all the pending RC_foo updates and persisting after paramMgr->sendPendingParameters(true, true); -} - -/// @brief This routine is called whenever a raw value for an RC channel changes. Depending on the current -/// calibration state, it will update internal values and ui accordingly. -/// @param chan RC channel on which signal is coming from (0-based) -/// @param fval Current value for channel -void PX4RCCalibration::_remoteControlChannelRawChanged(int chan, float fval) -{ - Q_ASSERT(chan >=0 && chan <= _chanMax); - - // We always update raw values - _rcRawValue[chan] = fval; - //qDebug() << "Raw value" << chan << fval; - - // Update state machine - switch (_rcCalState) { - case rcCalStateChannelWait: - // While we are waiting detect the minimum number of RC channels - if (chan + 1 > (int)_chanCount) { - _chanCount = chan + 1; - if (_chanCount >= _chanMinimum) { - _ui->rcCalNext->setEnabled(true); - _ui->rcCalStatus->setText(tr("Detected %1 radio channels.").arg(_chanCount)); - } else if (_chanCount < _chanMinimum) { - _ui->rcCalStatus->setText(tr("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); - } - } - - // Capture raw values so channel widgets are live - _rcRawValue[chan] = fval; - break; - - case rcCalStateIdentify: - if (!_rcCalStateChannelComplete) { - // If this channel is already used in a mapping we can't used it again - bool channelAlreadyMapped = !(_rgChannelInfo[chan].function == rcCalFunctionMax); - - // If the channel moved considerably, pick it - if (!channelAlreadyMapped && fabsf(_rcValueSave[chan] - fval) > _rcCalMoveDelta) { - Q_ASSERT(_rcCalStateCurrentChannel >= 0 && _rcCalStateCurrentChannel < rcCalFunctionMax); - _rgFunctionChannelMapping[_rcCalStateCurrentChannel] = chan; - _rgChannelInfo[chan].function = (enum rcCalFunctions)_rcCalStateCurrentChannel; - _updateView(); - - // Confirm found channel - QString msg = tr("Found %1 [Channel %2]").arg(_rgFunctionInfo[_rcCalStateCurrentChannel].functionName).arg(chan + 1); - _ui->rcCalFound->setText(msg); - //qDebug() << msg; - _ui->rcCalTryAgain->setEnabled(true); - _ui->rcCalNext->setEnabled(true); - _ui->rcCalSkip->setEnabled(false); - _rcCalStateChannelComplete =true; - } - } - break; - - case rcCalStateMinMax: - if (fval < _rgChannelInfo[chan].rcMin && fval <= _rcCalPWMValidMinValue) { - _rgRadioWidget[chan]->setMinValid(true); - _rgChannelInfo[chan].rcMin = fval; - } - if (fval > _rgChannelInfo[chan].rcMax && fval >= _rcCalPWMValidMaxValue) { - _rgRadioWidget[chan]->setMaxValid(true); - _rgChannelInfo[chan].rcMax = fval; - } - break; - - case rcCalStateCenterThrottle: - // If the throttle is roughly centered, enable the Next button - Q_ASSERT(_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax); - if (chan == _rgFunctionChannelMapping[rcCalFunctionThrottle] && - fabsf(fval - _rcCalPWMCenterPoint) < _rcCalRoughCenterDelta) { - _ui->rcCalNext->setEnabled(true); - } - break; - - case rcCalStateDetectInversion: - if (!_rcCalStateChannelComplete) { - // We only care about the channel we are looking for - Q_ASSERT(_rcCalStateCurrentChannel >= 0 && _rcCalStateCurrentChannel < rcCalFunctionMax); - if (chan == _rgFunctionChannelMapping[_rcCalStateCurrentChannel]) { - // If the channel moved considerably use it to determine inversion - //qDebug() << "Detect inversion" << chan << _rcValueSave[chan] << fval << _rcCalMoveDelta; - if (fabsf(_rcValueSave[chan] - fval) > _rcCalMoveDelta) { - // Request was made to move channel to a lower value. If value goes up the channel is reversed. - bool reversed = fval > _rcValueSave[chan]; - - _rgChannelInfo[chan].reversed = reversed; - _updateView(); - - // Confirm inversion detection - QString msg = tr("Channel for %1 ").arg(_rgFunctionInfo[_rcCalStateCurrentChannel].functionName); - if (reversed) { - msg += tr("is reversed."); - } else { - msg += tr("is not reversed."); - } - _ui->rcCalFound->setText(msg); - //qDebug() << msg; - _ui->rcCalTryAgain->setEnabled(true); - _ui->rcCalNext->setEnabled(true); - _ui->rcCalSkip->setEnabled(false); - _rcCalStateChannelComplete =true; - } - } - } - break; - - case rcCalStateTrims: - // Update the trim values for attitude functions only - if (_rgChannelInfo[chan].function >= rcCalFunctionFirstAttitudeFunction && _rgChannelInfo[chan].function <= rcCalFunctionLastAttitudeFunction) { - int mappedChannel = _rgFunctionChannelMapping[_rgChannelInfo[chan].function]; - - // All Attitude Functions should be mapped - Q_ASSERT(mappedChannel != rcCalFunctionMax); - - _rgChannelInfo[mappedChannel].rcTrim = _rcRawValue[mappedChannel]; - } - - // Once the throttle is lowered we enable the next button - Q_ASSERT(_rgFunctionChannelMapping[rcCalFunctionThrottle] != rcCalFunctionMax); - if (chan == _rgFunctionChannelMapping[rcCalFunctionThrottle]) { - bool enableNext = false; - - // If the value is close enough to min consider the throttle to be lowered (taking into account reversing) - if ((_rgChannelInfo[chan].reversed && fabsf(_rgChannelInfo[chan].rcMax - fval) < _rcCalMinDelta) || - fabsf(_rgChannelInfo[chan].rcMin - fval) < _rcCalMinDelta) { - enableNext = true; - } - _ui->rcCalNext->setEnabled(enableNext); - } - break; - default: - // Nothing special required for state - break; - } + _stopCalibration(); } void PX4RCCalibration::_updateView() { // Update the available channels for (int chan=0; chan<_chanCount; chan++) { - _rgRadioWidget[chan]->setEnabled(true); + RCValueWidget* valueWidget = _rgRCValueMonitorWidget[chan]; + + valueWidget->setVisible(true); + _rgRCValueMonitorLabel[chan]->setVisible(true); + //qDebug() << "Visible" << valueWidget->objectName() << chan; struct ChannelInfo* info = &_rgChannelInfo[chan]; - _rgRadioWidget[chan]->setValueAndMinMax(_rcRawValue[chan], info->rcMin, info->rcMax); - _rgRadioWidget[chan]->setTrim(info->rcTrim); - } - - // Disable non-available channels - for (int chan=_chanCount; chan<_chanMax; chan++) { - _rgRadioWidget[chan]->setEnabled(false); + valueWidget->setValueAndMinMax(_rcRawValue[chan], info->rcMin, info->rcMax); + valueWidget->setTrim(info->rcTrim); + valueWidget->setReversed(info->reversed); } - // Update the channel names for all channels - for (int chan=0; chan<_chanMax; chan++) { - struct ChannelInfo* info = &_rgChannelInfo[chan]; + // Update attitude controls + for (int i=0; i<_attitudeControls; i++) { + struct AttitudeInfo* attitudeInfo = &_rgAttitudeControl[i]; - QString name; - int oneBasedChannel = chan+1; - if (info->function == rcCalFunctionMax) { - name = tr("Channel %1").arg(oneBasedChannel); - } else { - QString label; - if (info->reversed) { - label = tr("%1 [Channel %2,Rev]"); - } else { - label = tr("%1 [Channel %2]"); - } - name = label.arg(_rgFunctionInfo[info->function].functionName).arg(oneBasedChannel); - } - _rgRadioWidget[chan]->setTitle(name); - } -} - -/// @brief Cancels the current calibration process and returns to the Channel Wait state. -void PX4RCCalibration::_rcCalCancel(void) -{ - _mav->endRadioControlCalibration(); - _rcCalChannelWait(true); - _setInternalCalibrationValuesFromParameters(); -} - -void PX4RCCalibration::_rcCalSkip(void) -{ - // Skip is only allowed for optional function mappings - Q_ASSERT(_rcCalState ==rcCalStateIdentify); - - // This will move us to the next function mapping - _rcCalNextIdentifyChannelMapping(); -} - -/// @brief Resets the state machine such that you can retry an identify or inversion detection on a specific -// function. -void PX4RCCalibration::_rcCalTryAgain(void) -{ - // FIXME: NYI for all states - QMessageBox::information(this, "Not Yet Implemented", "Try Again has not yet been implemented."); -} - -/// @brief Called when the Next button is called from the RC Calibration tab. This will either start the calibration process -/// or move it on to the next step. -void PX4RCCalibration::_rcCalNext(void) -{ - switch (_rcCalState) { - case rcCalStateChannelWait: - _rcCalBegin(); - break; + if (_rgFunctionChannelMapping[attitudeInfo->function] != _chanMax) { + int channel = _rgFunctionChannelMapping[attitudeInfo->function]; + struct ChannelInfo* info = &_rgChannelInfo[channel]; + RCValueWidget* valueWidget = attitudeInfo->valueWidget; - case rcCalStateBegin: - _rcCalStateCurrentChannel = -1; // _rcCalNextIdentifyChannelMapping will bump up to 0 to start sequence - _rcCalNextIdentifyChannelMapping(); - break; - - case rcCalStateIdentify: - _rcCalNextIdentifyChannelMapping(); - break; - - case rcCalStateMinMax: - _updateView(); - _rcCalCenterThrottle(); - break; - - case rcCalStateCenterThrottle: - // Setup for inversion detection channel - _rcCalStateCurrentChannel = rcCalFunctionFirstAttitudeFunction - 1; // _rcCalNextDetectChannelInversion will ++ to start sequence - _rcCalNextDetectChannelInversion(); - break; - - case rcCalStateDetectInversion: - _rcCalNextDetectChannelInversion(); - break; - - case rcCalStateTrims: - _rcCalSave(); - break; - - case rcCalStateSave: - _writeCalibration(false /* !trimsOnly */); - _rcCalChannelWait(false); - break; - - default: - Q_ASSERT(false); - break; - } -} - -/// @brief Setup for the Channel Wait state of calibration. -/// @param firstTime true: this is the first time a calibration is being performed since this widget was created -void PX4RCCalibration::_rcCalChannelWait(bool firstTime) -{ - _rcCalState = rcCalStateChannelWait; - - if (firstTime) { - _resetInternalCalibrationValues(); - } else { - _setInternalCalibrationValuesFromParameters(); - } - - if (_chanCount == 0) { - _ui->rcCalFound->setText(tr("Please turn on Radio")); - _ui->rcCalNext->setEnabled(false); - } else { - if (_chanCount >= _chanMinimum) { - _ui->rcCalNext->setEnabled(true); - _ui->rcCalStatus->setText(tr("Detected %1 radio channels.").arg(_chanCount)); - } else if (_chanCount < _chanMinimum) { - _ui->rcCalNext->setEnabled(false); - _ui->rcCalStatus->setText(tr("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); + attitudeInfo->valueWidget->setValueAndMinMax(_rcRawValue[channel], info->rcMin, info->rcMax); + valueWidget->setTrim(info->rcTrim); + valueWidget->setReversed(info->reversed); } } - if (firstTime) { - _ui->rcCalFound->clear(); - } else { - _ui->rcCalFound->setText(tr("Calibration complete")); + // Hide non-available channels + for (int chan=_chanCount; chan<_chanMax; chan++) { + _rgRCValueMonitorWidget[chan]->setVisible(false); + _rgRCValueMonitorLabel[chan]->setVisible(false); + //qDebug() << "Off" << _rgRCValueMonitorWidget[chan]->objectName() << chan; } - - _ui->rcCalNext->setText(tr("Start")); - _ui->rcCalCancel->setEnabled(false); - _ui->rcCalSkip->setEnabled(false); - _ui->rcCalTryAgain->setEnabled(false); } -/// @brief Set up for the Begin state of calibration. -void PX4RCCalibration::_rcCalBegin(void) +/// @brief Starts the calibration process +void PX4RCCalibration::_startCalibration(void) { Q_ASSERT(_chanCount >= _chanMinimum); - _rcCalState = rcCalStateBegin; - _resetInternalCalibrationValues(); // Let the mav known we are starting calibration. This should turn off motors and so forth. - // FIXME: XXX magic number: Set to 1 for radio input disable - _mav->startRadioControlCalibration(1); + _mav->startRadioControlCalibration(); _ui->rcCalNext->setText(tr("Next")); _ui->rcCalCancel->setEnabled(true); - _ui->rcCalStatus->setText(tr("Starting RC calibration.\n\n" - "Ensure RC transmitter and receiver are powered and connected. It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n" - "Reset all transmitter trims to center, then click Next to continue")); - _ui->rcCalFound->clear(); -} - -/// @brief Saves the current channel values, so that we can detect when the use moves an input. -void PX4RCCalibration::_rcCalSaveCurrentValues(void) -{ - //qDebug() << "_rcCalSaveCurrentValues"; - for (unsigned i = 0; i < _chanMax; i++) { - _rcValueSave[i] = _rcRawValue[i]; - } -} - -/// @brief Set up for the Identify state of calibration which assigns channels to control functions. -void PX4RCCalibration::_rcCalNextIdentifyChannelMapping(void) -{ - // Move to next channel - _rcCalStateCurrentChannel++; - Q_ASSERT(_rcCalStateCurrentChannel >= 0 && _rcCalStateCurrentChannel <= rcCalFunctionMax); - - // Be careful not to switch the state until we have a valid value in _rcCalStateCurrentChannel. Otherwise an rc signal could come through - // and cause _remoteControlChannelRawChanged to get confused. - _rcCalState = rcCalStateIdentify; - _rcCalStateChannelComplete = false; - - if (_rcCalStateCurrentChannel == rcCalFunctionMax) { - // If we have processed all channels move to next calibration step - _rcCalReadChannelsMinMax(); - return; - } - - // Save the current mapping, so we can reset if user decides to skip - _rcCalStateIdentifyOldMapping = _rgFunctionChannelMapping[_rcCalStateCurrentChannel]; - - // Save the current channel values so we can detect movement - _rcCalSaveCurrentValues(); - - _ui->rcCalStatus->setText(tr("Detecting %1 ...").arg(_rgFunctionInfo[_rcCalStateCurrentChannel].functionName)); - _ui->rcCalFound->setText(tr("Please move stick, switch or potentiometer for this channel all the way up/down or left/right.")); - - _ui->rcCalNext->setEnabled(false); - _ui->rcCalTryAgain->setEnabled(false); - _ui->rcCalSkip->setEnabled(!_rgFunctionInfo[_rcCalStateCurrentChannel].required); - _ui->rcCalCancel->setEnabled(true); -} - -/// @brief Sets up for the Min/Max state of calibration. -void PX4RCCalibration::_rcCalReadChannelsMinMax(void) -{ - _rcCalState = rcCalStateMinMax; - - _ui->rcCalStatus->setText(tr("Please move the sticks to their extreme positions, including all switches. Click Next when complete.")); - _ui->rcCalFound->clear(); - - _ui->rcCalNext->setEnabled(true); - _ui->rcCalTryAgain->setEnabled(false); - _ui->rcCalSkip->setEnabled(false); - _ui->rcCalCancel->setEnabled(true); - _showMinMaxOnRadioWidgets(true); + _currentStep = 0; + _setupCurrentState(); } -/// @brief Sets up for the Center Throttle state of Calibration which is required prior to detecting channel inversions. -void PX4RCCalibration::_rcCalCenterThrottle(void) +/// @brief Cancels the calibration process, setting things back to initial state. +void PX4RCCalibration::_stopCalibration(void) { - _rcCalState = rcCalStateCenterThrottle; + _currentStep = -1; - _ui->rcCalStatus->setText(tr("Next we will be determining which channels need to be reversed.\n\n" - "Please center the throttle stick prior to that. The stick should be roughly centered - the exact position is not relevant.\n" - "Once centered, leave it there until asked to move it.\n\n" - "Click the Next button when done. Next button will only enable when throttle is centered.")); - _ui->rcCalFound->clear(); - - _ui->rcCalNext->setEnabled(false); - _ui->rcCalTryAgain->setEnabled(false); - _ui->rcCalSkip->setEnabled(false); - _ui->rcCalCancel->setEnabled(true); -} - -/// @brief Set up the Detect Channel Inversion state of calibration. -void PX4RCCalibration::_rcCalNextDetectChannelInversion(void) -{ - // Move to next channel. We only detect inversion on Attitude control functions. - _rcCalStateCurrentChannel++; - Q_ASSERT(_rcCalStateCurrentChannel >= rcCalFunctionFirstAttitudeFunction && _rcCalStateCurrentChannel <= rcCalFunctionLastAttitudeFunction + 1); - if (_rcCalStateCurrentChannel > rcCalFunctionLastAttitudeFunction) { - // If we have processed all functions move to next calibration step - _rcCalTrims(); - return; + if (_mav) { + _mav->endRadioControlCalibration(); + _setInternalCalibrationValuesFromParameters(); + } else { + _resetInternalCalibrationValues(); } - // Be careful not to switch the state until we have a valid value in _rcCalStateCurrentChannel. Otherwise an rc signal could come through - // and cause _remoteControlChannelRawChanged to get confused. - _rcCalState = rcCalStateDetectInversion; - _rcCalStateChannelComplete = false; + _ui->rcCalStatus->clear(); - - // Save the current channel values so we can detect movement - _rcCalSaveCurrentValues(); - - const struct FunctionInfo* info = &_rgFunctionInfo[_rcCalStateCurrentChannel]; - - _ui->rcCalStatus->setText(tr("Detecting reversed channels: %1 ...").arg(info->functionName)); - _ui->rcCalFound->setText(info->inversionMsg); - - _ui->rcCalNext->setEnabled(false); - _ui->rcCalTryAgain->setEnabled(false); + _ui->rcCalNext->setText(tr("Calibrate")); + _ui->rcCalCancel->setEnabled(false); _ui->rcCalSkip->setEnabled(false); - _ui->rcCalCancel->setEnabled(true); } -/// @brief Set up the Trims state of calibration. -void PX4RCCalibration::_rcCalTrims(void) +/// @brief Saves the current channel values, so that we can detect when the use moves an input. +void PX4RCCalibration::_rcCalSaveCurrentValues(void) { - _rcCalState = rcCalStateTrims; - - _ui->rcCalStatus->setText(tr("Next we will be determining Trim values for the two attitude control sticks:\n" - "Please set the Throttle stick to the lowest throttle position and leave it there.\n" - "Click the Next button to save Trims. Next button will only enable when throttle is lowered.")); - _ui->rcCalFound->clear(); - - _ui->rcCalNext->setEnabled(false); - _ui->rcCalTryAgain->setEnabled(false); - _ui->rcCalSkip->setEnabled(false); - _ui->rcCalCancel->setEnabled(true); - - _showTrimOnRadioWidgets(true); + //qDebug() << "_rcCalSaveCurrentValues"; + for (unsigned i = 0; i < _chanMax; i++) { + _rcValueSave[i] = _rcRawValue[i]; + } } /// @brief Set up the Save state of calibration. @@ -788,10 +991,8 @@ void PX4RCCalibration::_rcCalSave(void) _ui->rcCalStatus->setText(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.")); - _ui->rcCalFound->clear(); _ui->rcCalNext->setEnabled(true); - _ui->rcCalTryAgain->setEnabled(false); _ui->rcCalSkip->setEnabled(false); _ui->rcCalCancel->setEnabled(true); @@ -802,55 +1003,13 @@ void PX4RCCalibration::_rcCalSave(void) _showMinMaxOnRadioWidgets(true); } -/// @brief This is used by unit test code to force the calibration state machine to the specified state. -/// With this you can write individual unit tests for each calibration state. Should only be called by -/// unit test code. -void PX4RCCalibration::_unitTestForceCalState(enum rcCalStates state) { - - switch (state) { - case rcCalStateBegin: - _rcCalBegin(); - break; - - case rcCalStateIdentify: - _rcCalStateCurrentChannel = -1; // _rcCalNextIdentifyChannelMapping will bump up to 0 to start sequence - _rcCalNextIdentifyChannelMapping(); - break; - - case rcCalStateMinMax: - _rcCalReadChannelsMinMax(); - break; - - case rcCalStateCenterThrottle: - _rcCalCenterThrottle(); - break; - - case rcCalStateDetectInversion: - _rcCalStateCurrentChannel = -1; // _rcCalNextDetectChannelInversion will bump up to 0 to start sequence - _rcCalNextDetectChannelInversion(); - break; - - case rcCalStateTrims: - _rcCalTrims(); - break; - - default: - // Unsupported force state - Q_ASSERT(false); - break; - } -} - /// @brief Shows or hides the min/max values of the channel widgets. /// @param show true: show the min/max values, false: hide the min/max values void PX4RCCalibration::_showMinMaxOnRadioWidgets(bool show) { - // Force a view update to widget have current values - _updateView(); - // Turn on min/max display for all radio widgets for (int i=0; i<_chanMax; i++) { - RCChannelWidget* radioWidget = _rgRadioWidget[i]; + RCValueWidget* radioWidget = _rgRCValueMonitorWidget[i]; Q_ASSERT(radioWidget); radioWidget->showMinMax(show); @@ -874,7 +1033,7 @@ void PX4RCCalibration::_showTrimOnRadioWidgets(bool show) { // Turn on trim display for all radio widgets for (int i=0; i<_chanMax; i++) { - RCChannelWidget* radioWidget = _rgRadioWidget[i]; + RCValueWidget* radioWidget = _rgRCValueMonitorWidget[i]; Q_ASSERT(radioWidget); radioWidget->showTrim(show); @@ -885,7 +1044,7 @@ void PX4RCCalibration::_parameterListUpToDate(void) { _parameterListUpToDateSignalled = true; - if (_rcCalState == rcCalStateChannelWait) { + if (_currentStep == -1) { _setInternalCalibrationValuesFromParameters(); } } diff --git a/src/ui/px4_configuration/PX4RCCalibration.h b/src/ui/px4_configuration/PX4RCCalibration.h index 3cb49554ba1bed83420b4059f36ac6f8f6ff0819..e5cdbc419f432852e1e229ddb3167b2419f06735 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.h +++ b/src/ui/px4_configuration/PX4RCCalibration.h @@ -32,8 +32,8 @@ #include #include -#include "QGCToolWidget.h" #include "UASInterface.h" +#include "RCValueWidget.h" #include "ui_PX4RCCalibration.h" @@ -52,18 +52,23 @@ class PX4RCCalibration : public QWidget public: explicit PX4RCCalibration(QWidget *parent = 0); + ~ PX4RCCalibration(); + +signals: + // @brief Signalled when in unit test mode and a message box should be displayed by the next button + void nextButtonMessageBoxDisplayed(void); private slots: - void _rcCalNext(void); - void _rcCalTryAgain(void); - void _rcCalSkip(void); - void _rcCalCancel(void); + void _nextButton(void); + void _skipButton(void); + void _spektrumBind(void); + + void _trimNYI(void); void _updateView(void); void _remoteControlChannelRawChanged(int chan, float val); void _setActiveUAS(UASInterface* uas); - void _toggleSpektrumPairing(bool enabled); void _parameterListUpToDate(void); @@ -105,52 +110,104 @@ private: rcCalStateSave }; + typedef void (PX4RCCalibration::*inputFn)(enum rcCalFunctions function, int chan, int value); + typedef void (PX4RCCalibration::*buttonFn)(void); + struct stateMachineEntry { + enum rcCalFunctions function; + const char* instructions; + const char* image; + inputFn rcInputFn; + buttonFn nextFn; + buttonFn skipFn; + }; + /// @brief A set of information associated with a function. struct FunctionInfo { - const char* functionName; ///< User visible function name - const char* inversionMsg; ///< Message to display to user to detect inversion const char* parameterName; ///< Parameter name for function mapping - bool required; ///< true: function must be mapped }; /// @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 - float rcMin; ///< Minimum RC value - float rcMax; ///< Maximum RC value - float rcTrim; ///< Trim position + int rcMin; ///< Minimum RC value + int rcMax; ///< Maximum RC value + int rcTrim; ///< Trim position + }; + + /// @brief Information to relate a function to it's value widget. + struct AttitudeInfo { + enum rcCalFunctions function; + RCValueWidget* valueWidget; }; // Methods - see source code for documentation + int _currentStep; ///< Current step of state machine + + const struct stateMachineEntry* _getStateMachineEntry(int step); + + void _nextStep(void); + void _setupCurrentState(void); + + 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 _inputFlapsDown(enum rcCalFunctions function, int channel, int value); + void _inputFlapsUp(enum rcCalFunctions function, int channel, int value); + void _inputSwitchDetect(enum rcCalFunctions function, int channel, int value); + void _inputFlapsDetect(enum rcCalFunctions function, int channel, int value); + + void _switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep); + + void _saveFlapsDown(void); + void _skipFlaps(void); + void _saveAllTrims(void); + + bool _stickSettleComplete(int value); + void _validateCalibration(void); - void _writeCalibration(bool trimsOnly); + void _writeCalibration(void); void _resetInternalCalibrationValues(void); void _setInternalCalibrationValuesFromParameters(void); - void _rcCalChannelWait(bool firstTime); - void _rcCalBegin(void); - void _rcCalNextIdentifyChannelMapping(void); - void _rcCalReadChannelsMinMax(void); - void _rcCalCenterThrottle(void); - void _rcCalNextDetectChannelInversion(void); - void _rcCalTrims(void); + void _startCalibration(void); + void _stopCalibration(void); void _rcCalSave(void); + void _writeParameters(void); + void _rcCalSaveCurrentValues(void); void _showMinMaxOnRadioWidgets(bool show); void _showTrimOnRadioWidgets(bool show); - void _unitTestForceCalState(enum rcCalStates state); + // @brief Called by unit test code to set the mode to unit testing + void _setUnitTestMode(void){ _unitTestMode = true; } // Member variables + + static const char* _imageFilePrefix; + static const char* _imageHome; + static const char* _imageThrottleUp; + static const char* _imageThrottleDown; + static const char* _imageYawLeft; + static const char* _imageYawRight; + static const char* _imageRollLeft; + static const char* _imageRollRight; + static const char* _imagePitchUp; + static const char* _imagePitchDown; + static const char* _imageSwitchMinMax; static const int _updateInterval; ///< Interval for ui update timer static const struct FunctionInfo _rgFunctionInfo[rcCalFunctionMax]; ///< Information associated with each function. int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function. + + static const int _attitudeControls = 5; + struct AttitudeInfo _rgAttitudeControl[_attitudeControls]; int _chanCount; ///< Number of actual rc channels available static const int _chanMax = 18; ///< Maximum number of supported rc channels @@ -169,16 +226,17 @@ private: static const int _rcCalPWMValidMaxValue; static const int _rcCalPWMDefaultMinValue; static const int _rcCalPWMDefaultMaxValue; - static const int _rcCalPWMDefaultTrimValue; static const int _rcCalRoughCenterDelta; - static const float _rcCalMoveDelta; - static const float _rcCalMinDelta; + static const int _rcCalMoveDelta; + static const int _rcCalSettleDelta; + static const int _rcCalMinDelta; - float _rcValueSave[_chanMax]; ///< Saved values prior to detecting channel movement + int _rcValueSave[_chanMax]; ///< Saved values prior to detecting channel movement - float _rcRawValue[_chanMax]; ///< Current set of raw channel values + int _rcRawValue[_chanMax]; ///< Current set of raw channel values - RCChannelWidget* _rgRadioWidget[_chanMax]; ///< Array of radio channel widgets + RCValueWidget* _rgRCValueMonitorWidget[_chanMax]; ///< Array of radio channel value widgets + QLabel* _rgRCValueMonitorLabel[_chanMax]; ///< Array of radio channel value labels UASInterface* _mav; ///< The current MAV QGCUASParamManagerInterface* _paramMgr; @@ -188,6 +246,15 @@ private: Ui::PX4RCCalibration* _ui; QTimer _updateTimer; ///< Timer used to update widgete ui + + int _stickDetectChannel; + int _stickDetectInitialValue; + int _stickDetectValue; + bool _stickDetectSettleStarted; + QTime _stickDetectSettleElapsed; + static const int _stickDetectSettleMSecs; + + bool _unitTestMode; }; #endif // PX4RCCalibration_H diff --git a/src/ui/px4_configuration/PX4RCCalibration.ui b/src/ui/px4_configuration/PX4RCCalibration.ui index b47a7a4929592027a368d14b20a9ce537e56ebf5..6a43cf186996c6db6942b1e341f8b3b9d7b5c8e4 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.ui +++ b/src/ui/px4_configuration/PX4RCCalibration.ui @@ -6,485 +6,1174 @@ 0 0 - 1562 + 831 1286 + + + 0 + 0 + + Form - - - - 760 - 0 - 252 - 715 - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - - 0 - 0 - 486 - 525 - - - - - - - - - - 0 - 0 - - - - - 0 - 180 - - - - Please turn on Radio - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - - 0 - 0 - - - - - 400 - 16 - - - - TextLabel - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - - - Try Again - - - - - - - Skip - - - - - - - Cancel - - - - - - - Next - - - - - - - - - Qt::Vertical - - - - 20 - 60 - - - - - - - - Spektrum RC - - - - + + + + + + + color: rgb(128, 128, 128); + + + QFrame::Plain + + + 1 + + + 0 + + + Qt::Horizontal + + + + + + + Receiver + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 40 + 20 + + + + + + + + Turn on transmitter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Spektrum Bind + + + + + + + + + color: rgb(128, 128, 128); + + + QFrame::Plain + + + 1 + + + Qt::Horizontal + + + + + + + Attitude Controls + + + + + + + + + + 0 + 0 + + + + + 61 + 24 + + + + + 16 + + + + border: 1px solid rgb(128, 128, 128); +border-radius: 4px; +background-color: rgb(80, 80, 80);s + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 30 + + + + + 400 + 16777215 + + + + + + + + + 0 + 30 + + + + + + + + + 0 + 0 + + + + + 45 + 0 + + + + + 16 + + + + + + + Trim + + + + + + + + 0 + 0 + + + + + 61 + 24 + + + + + 16 + + + + border: 1px solid rgb(128, 128, 128); +border-radius: 4px; +background-color: rgb(80, 80, 80);s + + + Throttle + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 45 + 0 + + + + + 16 + + + + + + + Trim + + + false + + + + + + + + 0 + 0 + + + + + 45 + 0 + + + + + 16 + + + + + + + Trim + + + + + + + + 0 + 0 + + + + + 45 + 0 + + + + + 16 + + + + + + + Trim + + + + + + + + 0 + 30 + + + + + + + + + 0 + 30 + + + + + + + + + 0 + 0 + + + + + 61 + 24 + + + + + 16 + + + + border: 1px solid rgb(128, 128, 128); +border-radius: 4px; +background-color: rgb(80, 80, 80);s + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 61 + 24 + + + + + 16 + + + + border: 1px solid rgb(128, 128, 128); +border-radius: 4px; +background-color: rgb(80, 80, 80);s + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 61 + 24 + + + + + 16 + + + + border: 1px solid rgb(128, 128, 128); +border-radius: 4px; +background-color: rgb(80, 80, 80);s + + + Flaps + + + Qt::AlignCenter + + + + + + + + 0 + 30 + + + + + + + + + + + 0 + 0 + + + + + 0 + 100 + + + + Please turn on Radio + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + + + Skip + + + + + + + Cancel + + + + + + + s + + + Start + + + + + + + + + Qt::Vertical + + + + 20 + 60 + + + + + + + + + + color: rgb(128, 128, 128); + + + QFrame::Plain + + + Qt::Vertical + + + + + + + + + color: rgb(128, 128, 128); + + + QFrame::Plain + + + Qt::Horizontal + + + + + + + Calibration Help + + + + + + + + 0 + 0 + + + + + 16777215 + 195 + + + + + + + :/files/images/px4/calibration/radioCenter.png + + + Qt::AlignCenter + + + + + + + color: rgb(128, 128, 128); + + + QFrame::Plain + + + 1 + + + Qt::Horizontal + + + + + + + + 0 + 0 + + + + Channel Monitor + + + + + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 9 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 2 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 7 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + - Pair Receiver + 8 - - + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + - DSM2 Mode + 5 + + + + + + + + 0 + 0 + - - true + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 1 - - + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + - DSMX Mode (3 to 7 channels) + 4 - - + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 6 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + - DSMX Mode (8 or more channels) + 3 + + + + + + + + 0 + 0 + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + + + + + 122 + 0 + + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 18 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 10 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 15 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 13 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 17 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 11 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 14 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 12 + + + + + + + + 0 + 0 + + + + border: 1px solid white; +border-radius: 4px; +background-color: rgb(179, 179, 179); + + + 16 + + + + + + + + 0 + 0 + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + + + + + + + + + 122 + 0 + - - - - - - - - - - 490 - 0 - 252 - 715 - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - - - - 250 - 65 - - - - - 250 - 65 - - - - - - + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - RCChannelWidget - QGroupBox -
ui/designer/RCChannelWidget.h
+ RCValueWidget + QWidget +
RCValueWidget.h
1
- + + + diff --git a/src/ui/px4_configuration/RCValueWidget.cc b/src/ui/px4_configuration/RCValueWidget.cc new file mode 100644 index 0000000000000000000000000000000000000000..1761f7294039a5c6e3dc9065fae4576d0523875a --- /dev/null +++ b/src/ui/px4_configuration/RCValueWidget.cc @@ -0,0 +1,306 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @author Don Gagne + +#include "RCValueWidget.h" + +#include +#include + +#define DIMMEST_COLOR QColor::fromRgb(0,100,0) +#define MIDBRIGHT_COLOR QColor::fromRgb(0,180,0) +#define BRIGHTEST_COLOR QColor::fromRgb(64,255,0) + +RCValueWidget::RCValueWidget(QWidget *parent) : + QWidget(parent), + _smallMode(false), + _value(_centerValue), + _min(_centerValue), + _max(_centerValue), + _trim(_centerValue), + _minValid(false), + _maxValid(false), + _showMinMax(false), + _showTrim(false), + _fgColor(255, 255, 255) +{ + setAutoFillBackground(true); +} + +/// @brief Draws the control +void RCValueWidget::paintEvent(QPaintEvent *event) +{ + QPainter painter(this); + painter.setRenderHints(QPainter::Antialiasing); + + Q_UNUSED(event); + + int curVal = _value; + if (curVal > _maxRange) { + curVal = _maxRange; + } + if (curVal < _minRange) { + curVal = _minRange; + } + + QPen pen(_fgColor); + pen.setWidth(1); + painter.setPen(pen); + + if (_smallMode) { + painter.drawLine(0, height() / 2, width(), height() / 2); + } else { + // The value bar itself it centered in the control + QRect rectValueBar(0, (rect().height() - _barHeight)/2, rect().width() - 1, _barHeight); + + painter.drawRoundedRect(rectValueBar, _barHeight/2, _barHeight/2); + } + + // Draw the RC value circle + int radius = _smallMode ? 4 : _barHeight; + int curValNormalized; + if (_reversed) { + curValNormalized = _centerValue - (curVal - _centerValue); + } else { + curValNormalized = curVal; + } + QPoint ptCenter(width() * ((float)(curValNormalized-_minRange) / (_maxRange-_minRange)), height() / 2); + QBrush brush(QColor(128, 128, 128)); + painter.setBrush(brush); + painter.drawEllipse(ptCenter, radius, radius); + +#if 0 + int fontHeight = painter.fontMetrics().height(); + int rowHeigth = fontHeight + 2; + + painter.setBrush(Qt::Dense4Pattern); + painter.setPen(QColor::fromRgb(128,128,64)); + + int curVal = _value; + if (curVal > _maxRange) { + curVal = _maxRange; + } + if (curVal < _minRange) { + curVal = _minRange; + } + + if (isEnabled()) { + QLinearGradient hGradientBrush(0, 0, this->width(), this->height()); + hGradientBrush.setColorAt(0.0,DIMMEST_COLOR); + hGradientBrush.setColorAt(0.5,MIDBRIGHT_COLOR); + hGradientBrush.setColorAt(1.0, BRIGHTEST_COLOR); + + // Calculate how much horizontal space we need to show a min/max value. We must be able to display four numeric + // digits for the rc value, plus we add another digit for spacing. + int minMaxDisplayWidth = painter.fontMetrics().width("00000"); + + // Draw the value axis line with center and end point tick marks. We need to leave enough space on the left and the right + // for the Min/Max value displays. + QRect rcValueAxis(minMaxDisplayWidth, rowHeigth * 2, width() - (minMaxDisplayWidth * 2), rowHeigth); + int yLine = rcValueAxis.y() + rcValueAxis.height() / 2; + painter.drawLine(rcValueAxis.left(), yLine, rcValueAxis.right(), yLine); + painter.drawLine(rcValueAxis.left(), rcValueAxis.top(), rcValueAxis.left(), rcValueAxis.bottom()); + painter.drawLine(rcValueAxis.right(), rcValueAxis.top(), rcValueAxis.right(), rcValueAxis.bottom()); + painter.drawLine(rcValueAxis.left() + rcValueAxis.width() / 2, rcValueAxis.top(), rcValueAxis.left() + rcValueAxis.width() / 2, rcValueAxis.bottom()); + + painter.setPen(QColor::fromRgb(50,255,50)); + painter.setBrush(hGradientBrush); + + if (_showMinMax) { + QString text; + + // Draw the Min numeric value display to the left + painter.drawText(0, rowHeigth, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, "Min"); + if (_minValid) { + text = QString::number(_min); + } else { + text = "----"; + } + painter.drawText(0, rowHeigth * 2, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, text); + + // Draw the Max numeric value display to the right + painter.drawText(width() - minMaxDisplayWidth, rowHeigth, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, "Max"); + if (_maxValid) { + text = QString::number(_max); + } else { + text = QString::number(_max); + } + painter.drawText(width() - minMaxDisplayWidth, rowHeigth * 2, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, text); + + // Draw the Min/Max tick marks on the axis + int xTick; + if (_minValid) { + int xTick = rcValueAxis.left() + (rcValueAxis.width() * ((float)(_min-_minRange) / (_maxRange-_minRange))); + painter.drawLine(xTick, rcValueAxis.top(), xTick, rcValueAxis.bottom()); + } + if (_maxValid) { + xTick = rcValueAxis.left() + (rcValueAxis.width() * ((float)(_max-_minRange) / (_maxRange-_minRange))); + painter.drawLine(xTick, rcValueAxis.top(), xTick, rcValueAxis.bottom()); + } + } + + if (_showTrim) { + // Draw the Trim value pointer + _drawValuePointer(&painter, + rcValueAxis.left() + (rcValueAxis.width() * ((float)(_trim-_minRange) / (_maxRange-_minRange))), // x position for tip of triangle + (rowHeigth * 2) + (rowHeigth / 2) - 1, // y position for tip of triangle + rowHeigth / 2, // heigth of triangle + false); // draw upside down + + // Draw the Trim value label + QString trimStr = tr("Trim %1").arg(QString::number(_trim)); + + int trimTextWidth = painter.fontMetrics().width(trimStr); + + painter.drawText(rcValueAxis.left() + (rcValueAxis.width() * ((float)(_trim-_minRange) / (_maxRange-_minRange))) - (trimTextWidth / 2), + rowHeigth, + trimTextWidth, + fontHeight, + Qt::AlignLeft | Qt::AlignBottom, + trimStr); + } + + // Draw the RC value pointer + _drawValuePointer(&painter, + rcValueAxis.left() + (rcValueAxis.width() * ((float)(curVal-_minRange) / (_maxRange-_minRange))), // x position for tip of triangle + (rowHeigth * 2) + (rowHeigth / 2) + 1, // y position for tip of triangle + rowHeigth / 2, // heigth of triangle + true); // draw right side up + + // Draw the control value + QString valueStr = QString::number(_value); + + int valueTextWidth = painter.fontMetrics().width(valueStr); + + painter.drawText(rcValueAxis.left() + (rcValueAxis.width() * ((float)(_value-_minRange) / (_maxRange-_minRange))) - (valueTextWidth / 2), + rowHeigth * 3, + valueTextWidth, + fontHeight, + Qt::AlignLeft | Qt::AlignBottom, + valueStr); + + painter.setPen(QColor::fromRgb(0,128,0)); + painter.setBrush(hGradientBrush); + } else { + painter.setPen(QColor(Qt::gray)); + painter.drawText(0, 0, width(), height(), Qt::AlignHCenter | Qt::AlignVCenter, tr("not available")); + } +#endif +} + +void RCValueWidget::setValue(int value) +{ + _value = value; + update(); +} + +void RCValueWidget::showMinMax(bool show) +{ + _showMinMax = show; + update(); +} + +void RCValueWidget::showTrim(bool show) +{ + _showTrim = show; + update(); +} + +void RCValueWidget::setValueAndMinMax(int val, int min, int max) +{ + setValue(val); + setMinMax(min,max); +} + +void RCValueWidget::setMinMax(int min, int max) +{ + _min = min; + _max = max; + update(); +} + +void RCValueWidget::setMin(int min) +{ + _min = min; + update(); +} + +void RCValueWidget::setMax(int max) +{ + _max = max; + update(); +} + +void RCValueWidget::setTrim(int value) +{ + _trim = value; + update(); +} + +/// @brief Draw rc value pointer triangle. +/// @param painter Draw using this painter +/// @param x X position for tip of triangle +/// @param y Y position for tip of triangle +/// @param heigth Height of triangle +/// @param rightSideUp true: draw triangle right side up, false: draw triangle upside down +void RCValueWidget::_drawValuePointer(QPainter* painter, int xTip, int yTip, int height, bool rightSideUp) +{ + QPointF trianglePoints[3]; + + // Topmost tip of triangle points to value + trianglePoints[0].setX(xTip); + trianglePoints[0].setY(yTip); + + int yBottom; + if (rightSideUp) { + yBottom = yTip + height; + } else { + yBottom = yTip - height; + } + + // Right bottom tip of triangle + trianglePoints[1].setX(xTip + (height * 0.75)); + trianglePoints[1].setY(yBottom); + + // Left bottom tip of triangle + trianglePoints[2].setX(xTip - (height * 0.75)); + trianglePoints[2].setY(yBottom); + + painter->drawPolygon (trianglePoints, 3); +} + +/// @brief Set whether the Min range value is valid or not. +void RCValueWidget::setMinValid(bool valid) +{ + _minValid = valid; + update(); +} + +/// @brief Set whether the Max range value is valid or not. +void RCValueWidget::setMaxValid(bool valid) +{ + _maxValid = valid; + update(); +} diff --git a/src/ui/px4_configuration/RCValueWidget.h b/src/ui/px4_configuration/RCValueWidget.h new file mode 100644 index 0000000000000000000000000000000000000000..03ce361f18ad36826137ddab59778385237a7116 --- /dev/null +++ b/src/ui/px4_configuration/RCValueWidget.h @@ -0,0 +1,111 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009, 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief Widget which shows current RC value on a bar with tick marks. +/// @author Don Gagne + +#ifndef RCValueWidget_H +#define RCValueWidget_H + +#include +#include + +/// @brief Widget which shows current RC value on a bar with tick marks. +class RCValueWidget : public QWidget +{ + Q_OBJECT + +public: + explicit RCValueWidget(QWidget *parent = 0); + + /// @brief Set the widget to display small value bar. + void setSmallMode(void) { _smallMode = true; } + + /// @brief Set the current RC value to display + void setValue(int value); + + /// @brief Set the current RC Value, Minimum RC Value and Maximum RC Value + void setValueAndMinMax(int val, int min, int max); + + void setMinMax(int min, int max); + void setMin(int min); + void setMax(int max); + + /// @brief Set whether the Min range value is valid or not. + void setMinValid(bool valid); + + /// @brief Set whether the Max range value is valid or not. + void setMaxValid(bool valid); + + /// @brief Sets the Trim value for the channel + void setTrim(int value); + + /// @brief Sets the reversed state of channel + /// @param reversed true: channel is reversed + void setReversed(bool reversed) { _reversed = reversed; } + + int value(void) { return _value; } ///< Returns the current RC Value set in the control + int min(void) { return _min; } ///< Returns the min value set in the control + int max(void) { return _max; } ///< Returns the max values set in the control + int trim(void) { return _trim; } ///< Returns the trim value set in the control + + void showMinMax(bool show); + bool isMinMaxShown() { return _showMinMax; } + bool isMinValid(void) { return _minValid; } + bool isMaxValid(void) { return _maxValid; } + + void showTrim(bool show); + bool isTrimShown() { return _showTrim; } + +protected: + virtual void paintEvent(QPaintEvent *event); + +private: + void _drawValuePointer(QPainter* painter, int xTip, int yTip, int height, bool rightSideUp); + + bool _smallMode; ///< true: draw small value bar, false: draw normal value bar + + int _value; ///< Current RC value + int _min; ///< Min RC value + int _max; ///< Max RC value + int _trim; ///< RC Value for Trim position + bool _reversed; ///< true: channel is reversed + + bool _minValid; ///< true: minimum value is valid + bool _maxValid; ///< true: maximum value is valid + + bool _showMinMax; ///< true: show min max values on display + bool _showTrim; ///< true: show trim value on display + + static const int _centerValue = 1500; ///< RC Value which is at center + static const int _maxDeltaRange = 650; ///< Delta around center value which is the max range for widget + static const int _minRange = _centerValue - _maxDeltaRange; ///< Smallest value widget can display + static const int _maxRange = _centerValue + _maxDeltaRange; ///< Largest value widget can display + + static const int _barHeight = 7; + + QColor _fgColor; +}; + +#endif