Commit 9f33e4b2 authored by Gus Grubba's avatar Gus Grubba

Handle setup page completed at the setup root level

parent 366305f9
......@@ -33,15 +33,9 @@ SetupPage {
readonly property string dialogTitle: qsTr("Radio")
property bool controllerCompleted: false
property bool controllerAndViewReady: false
Component.onCompleted: {
if (controllerCompleted) {
controllerAndViewReady = true
controller.start()
updateChannelCount()
}
onSetupPageCompleted: {
controller.start()
updateChannelCount()
}
function updateChannelCount()
......@@ -56,14 +50,6 @@ SetupPage {
cancelButton: cancelButton
nextButton: nextButton
skipButton: skipButton
Component.onCompleted: {
controllerCompleted = true
controllerAndViewReady = true
controller.start()
updateChannelCount()
}
onChannelCountChanged: updateChannelCount()
onFunctionMappingChangedAPMReboot: mainWindow.showMessageDialog(qsTr("Reboot required"), qsTr("Your stick mappings have changed, you must reboot the vehicle for correct operation."))
onThrottleReversedCalFailure: mainWindow.showMessageDialog(qsTr("Throttle channel reversed"), qsTr("Calibration failed. The throttle channel on your transmitter is reversed. You must correct this on your transmitter in order to complete calibration."))
......@@ -71,10 +57,8 @@ SetupPage {
Component {
id: copyTrimsDialogComponent
QGCViewMessage {
message: qsTr("Center your sticks and move throttle all the way down, then press Ok to copy trims. After pressing Ok, reset the trims on your radio back to zero.")
function accept() {
hideDialog()
controller.copyTrims()
......@@ -84,11 +68,9 @@ SetupPage {
Component {
id: zeroTrimsDialogComponent
QGCViewMessage {
message: qsTr("Before calibrating you should zero all your trims and subtrims. Click Ok to start Calibration.\n\n%1").arg(
(QGroundControl.multiVehicleManager.activeVehicle.px4Firmware ? "" : qsTr("Please ensure all motor power is disconnected AND all props are removed from the vehicle.")))
function accept() {
hideDialog()
controller.nextButtonClicked()
......@@ -98,7 +80,6 @@ SetupPage {
Component {
id: channelCountDialogComponent
QGCViewMessage {
message: controller.channelCount == 0 ? qsTr("Please turn on transmitter.") : qsTr("%1 channels or more are needed to fly.").arg(controller.minChannelCount)
}
......@@ -106,7 +87,6 @@ SetupPage {
Component {
id: spektrumBindDialogComponent
QGCViewDialog {
function accept() {
......
......@@ -22,7 +22,7 @@ QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "RadioComponentControll
#ifdef UNITTEST_BUILD
// Nasty hack to expose controller to unit test code
RadioComponentController* RadioComponentController::_unitTestController = NULL;
RadioComponentController* RadioComponentController::_unitTestController = nullptr;
#endif
const int RadioComponentController::_updateInterval = 150; ///< Interval for timer which updates radio channel widgets
......@@ -78,11 +78,6 @@ RadioComponentController::RadioComponentController(void)
, _transmitterMode(2)
, _chanCount(0)
, _rcCalState(rcCalStateChannelWait)
, _unitTestMode(false)
, _statusText(NULL)
, _cancelButton(NULL)
, _nextButton(NULL)
, _skipButton(NULL)
{
#ifdef UNITTEST_BUILD
// Nasty hack to expose controller to unit test code
......@@ -105,7 +100,7 @@ RadioComponentController::RadioComponentController(void)
// APM Stack has a bug where some RC params are missing. We need to know what these are so we can skip them if missing
// instead of popping missing param warnings.
_apmPossibleMissingRCChannelParams << 9 << 11 << 12 << 13 << 14;
_resetInternalCalibrationValues();
}
......@@ -140,37 +135,37 @@ const RadioComponentController::stateMachineEntry* RadioComponentController::_ge
static const char* msgPitchCenter = QT_TR_NOOP("Allow the Pitch stick to move back to center...");
static const char* msgSwitchMinMax = QT_TR_NOOP("Move all the transmitter switches and/or dials back and forth to their extreme positions.");
static const char* msgComplete = QT_TR_NOOP("All settings have been captured. Click Next to write the new parameters to your board.");
static const stateMachineEntry rgStateMachinePX4[] = {
//Function
{ rcCalFunctionMax, msgBeginPX4, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, NULL },
{ rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, NULL, NULL },
{ rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, NULL },
{ rcCalFunctionMax, msgComplete, _imageThrottleDown, NULL, &RadioComponentController::_writeCalibration, NULL },
{ rcCalFunctionMax, msgBeginPX4, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, nullptr },
{ rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, nullptr, nullptr },
{ rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, nullptr },
{ rcCalFunctionMax, msgComplete, _imageThrottleDown, nullptr, &RadioComponentController::_writeCalibration, nullptr },
};
static const stateMachineEntry rgStateMachineAPM[] = {
//Function
{ rcCalFunctionMax, msgBeginAPM, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, NULL },
{ rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, NULL, NULL },
{ rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, NULL, NULL },
{ rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, NULL, NULL },
{ rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, NULL },
{ rcCalFunctionMax, msgComplete, _imageThrottleDown, NULL, &RadioComponentController::_writeCalibration, NULL },
{ rcCalFunctionMax, msgBeginAPM, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, nullptr },
{ rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, nullptr, nullptr },
{ rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, nullptr, nullptr },
{ rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, nullptr, nullptr },
{ rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, nullptr },
{ rcCalFunctionMax, msgComplete, _imageThrottleDown, nullptr, &RadioComponentController::_writeCalibration, nullptr },
};
bool badStep = false;
......@@ -178,11 +173,11 @@ const RadioComponentController::stateMachineEntry* RadioComponentController::_ge
badStep = true;
}
if (_px4Vehicle()) {
if (step >= (int)(sizeof(rgStateMachinePX4) / sizeof(rgStateMachinePX4[0]))) {
if (step >= static_cast<int>(sizeof(rgStateMachinePX4) / sizeof(rgStateMachinePX4[0]))) {
badStep = true;
}
} else {
if (step >= (int)(sizeof(rgStateMachineAPM) / sizeof(rgStateMachineAPM[0]))) {
if (step >= static_cast<int>(sizeof(rgStateMachineAPM) / sizeof(rgStateMachineAPM[0]))) {
badStep = true;
}
}
......@@ -192,7 +187,7 @@ const RadioComponentController::stateMachineEntry* RadioComponentController::_ge
}
const stateMachineEntry* stateMachine = _px4Vehicle() ? rgStateMachinePX4 : rgStateMachineAPM;
return &stateMachine[step];
}
......@@ -220,14 +215,14 @@ void RadioComponentController::_setupCurrentState(void)
}
_statusText->setProperty("text", instructions);
_setHelpImage(helpImage);
_stickDetectChannel = _chanMax();
_stickDetectSettleStarted = false;
_rcCalSaveCurrentValues();
_nextButton->setEnabled(state->nextFn != NULL);
_skipButton->setEnabled(state->skipFn != NULL);
_nextButton->setEnabled(state->nextFn != nullptr);
_skipButton->setEnabled(state->skipFn != nullptr);
}
/// Connected to Vehicle::rcChannelsChanged signal
......@@ -277,7 +272,7 @@ void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValue
(this->*state->rcInputFn)(state->function, channel, channelValue);
}
} else {
qWarning() << "Internal error: NULL _getStateMachineEntry return";
qWarning() << "Internal error: nullptr _getStateMachineEntry return";
}
}
}
......@@ -302,7 +297,7 @@ void RadioComponentController::nextButtonClicked(void)
if (state && state->nextFn) {
(this->*state->nextFn)();
} else {
qWarning() << "Internal error: NULL _getStateMachineEntry return";
qWarning() << "Internal error: nullptr _getStateMachineEntry return";
}
}
}
......@@ -313,12 +308,12 @@ void RadioComponentController::skipButtonClicked(void)
qWarning() << "Internal error: _currentStep == -1";
return;
}
const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
if (state && state->skipFn) {
(this->*state->skipFn)();
} else {
qWarning() << "Internal error: NULL _getStateMachineEntry return";
qWarning() << "Internal error: nullptr _getStateMachineEntry return";
}
}
......@@ -333,7 +328,7 @@ void RadioComponentController::_saveAllTrims(void)
// 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++) {
qCDebug(RadioComponentControllerLog) << "_saveAllTrims channel trim" << i<< _rcRawValue[i];
_rgChannelInfo[i].rcTrim = _rcRawValue[i];
......@@ -347,63 +342,63 @@ void RadioComponentController::_inputCenterWaitBegin(enum rcCalFunctions functio
Q_UNUSED(function);
Q_UNUSED(chan);
Q_UNUSED(value);
// FIXME: Doesn't wait for center
_nextButton->setEnabled(true);
}
bool RadioComponentController::_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
qCDebug(RadioComponentControllerLog) << "_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
qCDebug(RadioComponentControllerLog) << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value;
_stickDetectSettleStarted = true;
_stickDetectSettleElapsed.start();
}
}
return false;
}
void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, int channel, int value)
{
qCDebug(RadioComponentControllerLog) << "_inputStickDetect function:channel:value" << _functionInfo()[function].parameterName << channel << value;
// If this channel is already used in a mapping we can't use it again
if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
return;
}
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
qCDebug(RadioComponentControllerLog) << "_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;
......@@ -412,15 +407,15 @@ void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, i
} else if (channel == _stickDetectChannel) {
if (_stickSettleComplete(value)) {
ChannelInfo* info = &_rgChannelInfo[channel];
// 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];
qCDebug(RadioComponentControllerLog) << "_inputStickDetect settle complete, function:channel:value:reversed" << function << channel << value << info->reversed;
if (info->reversed) {
......@@ -428,9 +423,9 @@ void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, i
} else {
_rgChannelInfo[channel].rcMax = value;
}
_signalAllAttitudeValueChanges();
_advanceState();
}
}
......@@ -460,10 +455,10 @@ void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int
}
} else {
// We are waiting for the selected channel to settle out
if (_stickSettleComplete(value)) {
ChannelInfo* info = &_rgChannelInfo[channel];
// Stick detection is complete. Stick should be at min position.
if (info->reversed) {
_rgChannelInfo[channel].rcMax = value;
......@@ -477,7 +472,7 @@ void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int
}
// XXX to support configs which can reverse they need to check a reverse
// flag here and not do this.
_advanceState();
}
}
......@@ -489,10 +484,10 @@ void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, in
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;
......@@ -515,20 +510,20 @@ void RadioComponentController::_inputSwitchMinMax(enum rcCalFunctions function,
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);
qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting min channel:min" << channel << minValue;
_rgChannelInfo[channel].rcMin = minValue;
} else {
int maxValue = qMax(_rgChannelInfo[channel].rcMax, value);
qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue;
_rgChannelInfo[channel].rcMax = maxValue;
}
}
......@@ -540,19 +535,19 @@ void RadioComponentController::_switchDetect(enum rcCalFunctions function, int c
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;
qCDebug(RadioComponentControllerLog) << "Function:" << function << "mapped to:" << channel;
if (moveToNextStep) {
_advanceState();
}
......@@ -576,12 +571,12 @@ void RadioComponentController::_resetInternalCalibrationValues(void)
info->rcMax = RadioComponentController::_rcCalPWMCenterPoint;
info->rcTrim = RadioComponentController::_rcCalPWMCenterPoint;
}
// Initialize attitude function mapping to function channel not set
for (size_t i=0; i<rcCalFunctionMax; i++) {
_rgFunctionChannelMapping[i] = _chanMax();
}
_signalAllAttitudeValueChanges();
}
......@@ -589,22 +584,22 @@ void RadioComponentController::_resetInternalCalibrationValues(void)
void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
{
// Initialize all function mappings to not set
for (int i=0; i<_chanMax(); i++) {
struct ChannelInfo* info = &_rgChannelInfo[i];
info->function = rcCalFunctionMax;
}
for (size_t i=0; i<rcCalFunctionMax; i++) {
_rgFunctionChannelMapping[i] = _chanMax();
}
// Pull parameters and update
QString minTpl("RC%1_MIN");
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
for (int i = 0; i < _chanMax(); ++i) {
struct ChannelInfo* info = &_rgChannelInfo[i];
......@@ -618,12 +613,12 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
continue;
}
}
Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1));
if (paramFact) {
info->rcTrim = paramFact->rawValue().toInt();
}
paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1));
if (paramFact) {
info->rcMin = paramFact->rawValue().toInt();
......@@ -636,10 +631,10 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
info->reversed = _channelReversedParamValue(i);
}
for (int i=0; i<rcCalFunctionMax; i++) {
int32_t paramChannel;
const char* paramName = _functionInfo()[i].parameterName;
if (paramName) {
Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, paramName);
......@@ -648,12 +643,12 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
if (paramChannel > 0 && paramChannel <= _chanMax()) {
_rgFunctionChannelMapping[i] = paramChannel - 1;
_rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i;
_rgChannelInfo[paramChannel - 1].function = static_cast<rcCalFunctions>(i);
}
}
}
}
_signalAllAttitudeValueChanges();
}
......@@ -667,7 +662,7 @@ void RadioComponentController::_validateCalibration(void)
{
for (int chan = 0; chan<_chanMax(); chan++) {
struct ChannelInfo* info = &_rgChannelInfo[chan];
if (chan < _chanCount) {
// 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.
......@@ -694,7 +689,7 @@ void RadioComponentController::_validateCalibration(void)
info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
break;
}
}
} else {
// Unavailable channels are set to defaults
......@@ -712,7 +707,7 @@ void RadioComponentController::_validateCalibration(void)
void RadioComponentController::_writeCalibration(void)
{
if (!_uas) return;
if (_px4Vehicle()) {
_uas->stopCalibration();
}
......@@ -740,15 +735,15 @@ void RadioComponentController::_writeCalibration(void)
Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel));
if (paramFact) {
paramFact->setRawValue((float)info->rcTrim);
paramFact->setRawValue(static_cast<float>(info->rcTrim));
}
paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel));
if (paramFact) {
paramFact->setRawValue((float)info->rcMin);
paramFact->setRawValue(static_cast<float>(info->rcMin));
}
paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel));
if (paramFact) {
paramFact->setRawValue((float)info->rcMax);
paramFact->setRawValue(static_cast<float>(info->rcMax));
}
// For multi-rotor we can determine reverse setting during radio cal. For anything other than multi-rotor, servo installation
......@@ -795,7 +790,7 @@ void RadioComponentController::_writeCalibration(void)
getParameterFact(FactSystem::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))->setRawValue(_chanCount);
}
}
_stopCalibration();
_setInternalCalibrationValuesFromParameters();
}
......@@ -807,17 +802,17 @@ void RadioComponentController::_startCalibration(void)
qWarning() << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum";
return;
}
_resetInternalCalibrationValues();
// Let the mav known we are starting calibration. This should turn off motors and so forth.
if (_px4Vehicle()) {
_uas->startCalibration(UASInterface::StartCalibrationRadio);
}
_nextButton->setProperty("text", tr("Next"));
_cancelButton->setEnabled(true);
_currentStep = 0;
_setupCurrentState();
}
......@@ -826,7 +821,7 @@ void RadioComponentController::_startCalibration(void)
void RadioComponentController::_stopCalibration(void)
{
_currentStep = -1;
if (_uas) {
if (_px4Vehicle()) {
_uas->stopCalibration();
......@@ -835,14 +830,13 @@ void RadioComponentController::_stopCalibration(void)
} else {
_resetInternalCalibrationValues();
}
_statusText->setProperty("text", "");
_nextButton->setProperty("text", tr("Calibrate"));
_nextButton->setEnabled(true);
_cancelButton->setEnabled(false);
_skipButton->setEnabled(false);
if(_statusText) _statusText->setProperty("text", "");
if(_nextButton) _nextButton->setProperty("text", tr("Calibrate"));
if(_nextButton) _nextButton->setEnabled(true);
if(_cancelButton) _cancelButton->setEnabled(false);
if(_skipButton) _skipButton->setEnabled(false);
_setHelpImage(_imageCenter);
}
......@@ -859,15 +853,16 @@ void RadioComponentController::_rcCalSaveCurrentValues(void)
void RadioComponentController::_rcCalSave(void)
{
_rcCalState = rcCalStateSave;
_statusText->setProperty("text",
tr("The current calibration settings are now displayed for each channel on screen.\n\n"
"Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."));
_nextButton->setEnabled(true);
_skipButton->setEnabled(false);
_cancelButton->setEnabled(true);
if(_statusText) _statusText->setProperty(
"text",
tr("The current calibration settings are now displayed for each channel on screen.\n\n"
"Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."));
if(_nextButton) _nextButton->setEnabled(true);
if(_skipButton) _skipButton->setEnabled(false);
if(_cancelButton) _cancelButton->setEnabled(true);
// This updates the internal values according to the validation rules. Then _updateView will tick and update ui
// such that the settings that will be written our are displayed.
_validateCalibration();
......@@ -876,11 +871,11 @@ void RadioComponentController::_rcCalSave(void)
void RadioComponentController::_loadSettings(void)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
_transmitterMode = settings.value(_settingsKeyTransmitterMode, 2).toInt();
settings.endGroup();
if (_transmitterMode != 1 || _transmitterMode != 2) {
_transmitterMode = 2;
}
......@@ -889,7 +884,7 @@ void RadioComponentController::_loadSettings(void)
void RadioComponentController::_storeSettings(void)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_settingsKeyTransmitterMode, _transmitterMode);
settings.endGroup();
......@@ -898,7 +893,7 @@ void RadioComponentController::_storeSettings(void)
void RadioComponentController::_setHelpImage(const char* imageFile)
{
QString file = _imageFilePrefix;
if (_transmitterMode == 1) {
file += _imageFileMode1Dir;
} else if (_transmitterMode == 2) {
......@@ -908,9 +903,9 @@ void RadioComponentController::_setHelpImage(const char* imageFile)
return;
}
file += imageFile;
qCDebug(RadioComponentControllerLog) << "_setHelpImage" << file;
_imageHelp = file;
emit imageHelpChanged(file);
}
......@@ -921,7 +916,7 @@ int RadioComponentController::channelCount(void)
}
int RadioComponentController::rollChannelRCValue(void)
{
{
if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
return _rcRawValue[rcCalFunctionRoll];
} else {
......@@ -1029,7 +1024,7 @@ void RadioComponentController::_signalAllAttitudeValueChanges(void)
emit pitchChannelMappedChanged(pitchChannelMapped());
emit yawChannelMappedChanged(yawChannelMapped());
emit throttleChannelMappedChanged(throttleChannelMapped());
emit rollChannelReversedChanged(rollChannelReversed());
emit pitchChannelReversedChanged(pitchChannelReversed());
emit yawChannelReversedChanged(yawChannelReversed());
......
......@@ -36,36 +36,36 @@ namespace Ui {
class RadioComponentController : public FactPanelController
{
Q_OBJECT
friend class RadioConfigTest; ///< This allows our unit test to access internal information needed.
public:
RadioComponentController(void);
~RadioComponentController();
Q_PROPERTY(int minChannelCount MEMBER _chanMinimum CONSTANT)
Q_PROPERTY(int channelCount READ channelCount NOTIFY channelCountChanged)
Q_PROPERTY(QQuickItem* statusText MEMBER _statusText NOTIFY statusTextChanged)
Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton NOTIFY cancelButtonChanged)
Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton NOTIFY nextButtonChanged)
Q_PROPERTY(QQuickItem* skipButton MEMBER _skipButton NOTIFY skipButtonChanged)
Q_PROPERTY(bool rollChannelMapped READ rollChannelMapped NOTIFY rollChannelMappedChanged)
Q_PROPERTY(bool pitchChannelMapped READ pitchChannelMapped NOTIFY pitchChannelMappedChanged)
Q_PROPERTY(bool yawChannelMapped READ yawChannelMapped NOTIFY yawChannelMappedChanged)
Q_PROPERTY(bool throttleChannelMapped READ throttleChannelMapped NOTIFY throttleChannelMappedChanged)
Q_PROPERTY(int rollChannelRCValue READ rollChannelRCValue NOTIFY rollChannelRCValueChanged)
Q_PROPERTY(int pitchChannelRCValue READ pitchChannelRCValue NOTIFY pitchChannelRCValueChanged)
Q_PROPERTY(int yawChannelRCValue READ yawChannelRCValue NOTIFY yawChannelRCValueChanged)
Q_PROPERTY(int throttleChannelRCValue READ throttleChannelRCValue NOTIFY throttleChannelRCValueChanged)
Q_PROPERTY(int rollChannelReversed READ rollChannelReversed NOTIFY rollChannelReversedChanged)
Q_PROPERTY(int pitchChannelReversed READ pitchChannelReversed NOTIFY pitchChannelReversedChanged)
Q_PROPERTY(int yawChannelReversed READ yawChannelReversed NOTIFY yawChannelReversedChanged)
Q_PROPERTY(int throttleChannelReversed READ throttleChannelReversed NOTIFY throttleChannelReversedChanged)
Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged)
Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged)
......@@ -82,27 +82,27 @@ public:
Q_INVOKABLE void nextButtonClicked(void);
Q_INVOKABLE void start(void);
Q_INVOKABLE void copyTrims(void);
int rollChannelRCValue(void);
int pitchChannelRCValue(void);
int yawChannelRCValue(void);
int throttleChannelRCValue(void);
bool rollChannelMapped(void);
bool pitchChannelMapped(void);
bool yawChannelMapped(void);
bool throttleChannelMapped(void);
bool rollChannelReversed(void);
bool pitchChannelReversed(void);
bool yawChannelReversed(void);
bool throttleChannelReversed(void);
int channelCount(void);
int transmitterMode(void) { return _transmitterMode; }
void setTransmitterMode(int mode);
signals:
void statusTextChanged(void);
void cancelButtonChanged(void);
......@@ -111,25 +111,25 @@ signals:
void channelCountChanged(int channelCount);
void channelRCValueChanged(int channel, int rcValue);
void rollChannelMappedChanged(bool mapped);
void pitchChannelMappedChanged(bool mapped);
void yawChannelMappedChanged(bool mapped);
void throttleChannelMappedChanged(bool mapped);
void rollChannelRCValueChanged(int rcValue);
void pitchChannelRCValueChanged(int rcValue);
void yawChannelRCValueChanged(int rcValue);
void throttleChannelRCValueChanged(int rcValue);
void rollChannelReversedChanged(bool reversed);
void pitchChannelReversedChanged(bool reversed);
void yawChannelReversedChanged(bool reversed);
void throttleChannelReversedChanged(bool reversed);
void imageHelpChanged(QString source);
void transmitterModeChanged(int mode);
/// Signalled when in unit test mode and a message box should be displayed by the next button
void nextButtonMessageBoxDisplayed(void);
......@@ -152,7 +152,7 @@ private:
rcCalFunctionThrottle,
rcCalFunctionMax,
};
/// @brief The states of the calibration state machine.
enum rcCalStates {
rcCalStateChannelWait,
......@@ -164,7 +164,7 @@ private:
rcCalStateTrims,
rcCalStateSave
};
typedef void (RadioComponentController::*inputFn)(enum rcCalFunctions function, int chan, int value);
typedef void (RadioComponentController::*buttonFn)(void);
struct stateMachineEntry {
......@@ -175,12 +175,12 @@ private:
buttonFn nextFn;
buttonFn skipFn;
};
/// @brief A set of information associated with a function.
struct FunctionInfo {
const char* parameterName; ///< Parameter name for function mapping
};
/// @brief A set of information associated with a radio channel.
struct ChannelInfo {
enum rcCalFunctions function; ///< Function mapped to this channel, rcCalFunctionMax for none
......@@ -189,47 +189,47 @@ private:
int rcMax; ///< Maximum RC value
int rcTrim; ///< Trim position
};
int _currentStep; ///< Current step of state machine
const struct stateMachineEntry* _getStateMachineEntry(int step) const;
const struct FunctionInfo* _functionInfo(void) const;
bool _px4Vehicle(void) const;
void _advanceState(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 _inputSwitchDetect(enum rcCalFunctions function, int channel, int value);
void _switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep);
void _saveAllTrims(void);
bool _stickSettleComplete(int value);
void _validateCalibration(void);
void _writeCalibration(void);
void _resetInternalCalibrationValues(void);
void _setInternalCalibrationValuesFromParameters(void);
void _startCalibration(void);
void _stopCalibration(void);
void _rcCalSave(void);
void _writeParameters(void);
void _rcCalSaveCurrentValues(void);
void _setHelpImage(const char* imageFile);
void _loadSettings(void);
void _storeSettings(void);
void _signalAllAttitudeValueChanges(void);
int _chanMax(void) const;
......@@ -239,7 +239,7 @@ private:
// @brief Called by unit test code to set the mode to unit testing
void _setUnitTestMode(void){ _unitTestMode = true; }
// Member variables
static const char* _imageFileMode1Dir;
......@@ -256,12 +256,12 @@ private:
static const char* _imagePitchUp;
static const char* _imagePitchDown;
static const char* _imageSwitchMinMax;
static const char* _settingsGroup;
static const char* _settingsKeyTransmitterMode;
int _transmitterMode; ///< 1: transmitter is mode 1, 2: transmitted is mode 2
static const int _updateInterval; ///< Interval for ui update timer
static const struct FunctionInfo _rgFunctionInfoAPM[rcCalFunctionMax]; ///< Information associated with each function, PX4 firmware
......@@ -280,13 +280,13 @@ private:
struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel
QList<int> _apmPossibleMissingRCChannelParams; ///< List of possible missing RC*_* params for APM stack
enum rcCalStates _rcCalState; ///< Current calibration state
int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion
bool _rcCalStateChannelComplete; ///< Work associated with current channel is complete
int _rcCalStateIdentifyOldMapping; ///< Previous mapping for channel being currently identified
int _rcCalStateReverseOldMapping; ///< Previous mapping for channel being currently used to detect inversion
static const int _rcCalPWMCenterPoint;
static const int _rcCalPWMValidMinValue;
static const int _rcCalPWMValidMaxValue;
......@@ -303,25 +303,25 @@ private:
bool _revParamIsBool;
int _rcValueSave[_chanMaxAny]; ///< Saved values prior to detecting channel movement
int _rcRawValue[_chanMaxAny]; ///< Current set of raw channel values
int _stickDetectChannel;
int _stickDetectInitialValue;
int _stickDetectValue;
bool _stickDetectSettleStarted;
QTime _stickDetectSettleElapsed;
static const int _stickDetectSettleMSecs;
bool _unitTestMode;
QQuickItem* _statusText;
QQuickItem* _cancelButton;
QQuickItem* _nextButton;
QQuickItem* _skipButton;
bool _unitTestMode = false;
QQuickItem* _statusText = nullptr;
QQuickItem* _cancelButton = nullptr;
QQuickItem* _nextButton = nullptr;
QQuickItem* _skipButton = nullptr;
QString _imageHelp;
#ifdef UNITTEST_BUILD
// Nasty hack to expose controller to unit test code
static RadioComponentController* _unitTestController;
......
......@@ -25,13 +25,14 @@ Item {
id: setupView
enabled: !_disableDueToArmed && !_disableDueToFlying
property alias pageComponent: pageLoader.sourceComponent
property string pageName: vehicleComponent ? vehicleComponent.name : ""
property string pageDescription: vehicleComponent ? vehicleComponent.description : ""
property real availableWidth: width - pageLoader.x
property real availableHeight: height - pageLoader.y
property bool showAdvanced: false
property alias advanced: advancedCheckBox.checked
property alias pageComponent: pageLoader.sourceComponent
property string pageName: vehicleComponent ? vehicleComponent.name : ""
property string pageDescription: vehicleComponent ? vehicleComponent.description : ""
property real availableWidth: width - pageLoader.x
property real availableHeight: height - pageLoader.y
property bool showAdvanced: false
property alias advanced: advancedCheckBox.checked
property bool setupPageCompleted: false
property bool _vehicleIsRover: activeVehicle ? activeVehicle.rover : false
property bool _vehicleArmed: activeVehicle ? activeVehicle.armed : false
......@@ -43,6 +44,10 @@ Item {
property real _margins: ScreenTools.defaultFontPixelHeight * 0.5
property string _pageTitle: qsTr("%1 Setup").arg(pageName)
Component.onCompleted: {
setupPageCompleted = true
}
QGCFlickable {
anchors.fill: parent
contentWidth: pageLoader.x + pageLoader.item.width
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment