RadioComponentController.cc 44.2 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10 11

/// @file
Don Gagne's avatar
Don Gagne committed
12
///     @brief Radio Config Qml Controller
13 14
///     @author Don Gagne <don@thegagnes.com

Don Gagne's avatar
Don Gagne committed
15
#include "RadioComponentController.h"
Don Gagne's avatar
Don Gagne committed
16
#include "QGCApplication.h"
17

18
#include <QElapsedTimer>
Don Gagne's avatar
Don Gagne committed
19 20 21
#include <QSettings>

QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "RadioComponentControllerLog")
22
QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "RadioComponentControllerVerboseLog")
23

24 25
#ifdef UNITTEST_BUILD
// Nasty hack to expose controller to unit test code
26
RadioComponentController* RadioComponentController::_unitTestController = nullptr;
27 28
#endif

Don Gagne's avatar
Don Gagne committed
29 30
const int RadioComponentController::_updateInterval = 150;              ///< Interval for timer which updates radio channel widgets
const int RadioComponentController::_rcCalPWMCenterPoint = ((RadioComponentController::_rcCalPWMValidMaxValue - RadioComponentController::_rcCalPWMValidMinValue) / 2.0f) + RadioComponentController::_rcCalPWMValidMinValue;
31 32 33 34 35 36 37 38
const int RadioComponentController::_rcCalPWMValidMinValue =    1300;   ///< Largest valid minimum PWM Min range value
const int RadioComponentController::_rcCalPWMValidMaxValue =    1700;   ///< Smallest valid maximum PWM Max range value
const int RadioComponentController::_rcCalPWMDefaultMinValue =  1000;   ///< Default value for Min if not set
const int RadioComponentController::_rcCalPWMDefaultMaxValue =  2000;   ///< Default value for Max if not set
const int RadioComponentController::_rcCalRoughCenterDelta =    50;     ///< Delta around center point which is considered to be roughly centered
const int RadioComponentController::_rcCalMoveDelta =           300;    ///< Amount of delta past center which is considered stick movement
const int RadioComponentController::_rcCalSettleDelta =         20;     ///< Amount of delta which is considered no stick movement
const int RadioComponentController::_rcCalMinDelta =            100;    ///< Amount of delta allowed around min value to consider channel at min
Don Gagne's avatar
Don Gagne committed
39 40 41

const int RadioComponentController::_stickDetectSettleMSecs = 500;

42
const char*  RadioComponentController::_imageFilePrefix =   "calibration/";
Don Gagne's avatar
Don Gagne committed
43 44
const char*  RadioComponentController::_imageFileMode1Dir = "mode1/";
const char*  RadioComponentController::_imageFileMode2Dir = "mode2/";
45 46 47
const char*  RadioComponentController::_imageCenter =       "radioCenter.png";
const char*  RadioComponentController::_imageHome =         "radioHome.png";
const char*  RadioComponentController::_imageThrottleUp =   "radioThrottleUp.png";
Don Gagne's avatar
Don Gagne committed
48
const char*  RadioComponentController::_imageThrottleDown = "radioThrottleDown.png";
49 50 51 52 53 54
const char*  RadioComponentController::_imageYawLeft =      "radioYawLeft.png";
const char*  RadioComponentController::_imageYawRight =     "radioYawRight.png";
const char*  RadioComponentController::_imageRollLeft =     "radioRollLeft.png";
const char*  RadioComponentController::_imageRollRight =    "radioRollRight.png";
const char*  RadioComponentController::_imagePitchUp =      "radioPitchUp.png";
const char*  RadioComponentController::_imagePitchDown =    "radioPitchDown.png";
Don Gagne's avatar
Don Gagne committed
55 56
const char*  RadioComponentController::_imageSwitchMinMax = "radioSwitchMinMax.png";

57
const char* RadioComponentController::_settingsGroup =              "RadioCalibration";
Don Gagne's avatar
Don Gagne committed
58 59
const char* RadioComponentController::_settingsKeyTransmitterMode = "TransmitterMode";

60 61 62
const char* RadioComponentController::_px4RevParamFormat =      "RC%1_REV";
const char* RadioComponentController::_apmNewRevParamFormat =   "RC%1_REVERSED";

Don Gagne's avatar
Don Gagne committed
63
const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfoPX4[RadioComponentController::rcCalFunctionMax] = {
64 65 66 67
{ "RC_MAP_ROLL" },
{ "RC_MAP_PITCH" },
{ "RC_MAP_YAW" },
{ "RC_MAP_THROTTLE" }
68 69
};

Don Gagne's avatar
Don Gagne committed
70
const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfoAPM[RadioComponentController::rcCalFunctionMax] = {
71 72 73 74
{ "RCMAP_ROLL" },
{ "RCMAP_PITCH" },
{ "RCMAP_YAW" },
{ "RCMAP_THROTTLE" }
Don Gagne's avatar
Don Gagne committed
75 76
};

77 78 79 80 81
RadioComponentController::RadioComponentController(void)
    : _currentStep(-1)
    , _transmitterMode(2)
    , _chanCount(0)
    , _rcCalState(rcCalStateChannelWait)
82
{
83 84 85 86 87
#ifdef UNITTEST_BUILD
    // Nasty hack to expose controller to unit test code
    _unitTestController = this;
#endif

88 89 90 91 92 93 94 95 96 97
    if (parameterExists(FactSystem::defaultComponentId, QStringLiteral("RC1_REVERSED"))) {
        // Newer ardupilot firmwares have a different reverse param naming scheme and value scheme
        _revParamFormat = _apmNewRevParamFormat;
        _revParamIsBool = true; // param value is boolean 0/1 for reversed or not
    } else {
        // Older ardupilot firmwares share the same naming convention as PX4
        _revParamFormat = _px4RevParamFormat;
        _revParamIsBool = false;    // paeram value if -1 indicates reversed
    }

Don Gagne's avatar
Don Gagne committed
98
    connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged);
99
    _loadSettings();
100 101 102 103

    // 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;
104

Don Gagne's avatar
Don Gagne committed
105 106 107 108 109
    _resetInternalCalibrationValues();
}

void RadioComponentController::start(void)
{
Don Gagne's avatar
Don Gagne committed
110
    _stopCalibration();
111
    _setInternalCalibrationValuesFromParameters();
Don Gagne's avatar
Don Gagne committed
112
}
113

Don Gagne's avatar
Don Gagne committed
114
RadioComponentController::~RadioComponentController()
Don Gagne's avatar
Don Gagne committed
115
{
116
    _storeSettings();
Don Gagne's avatar
Don Gagne committed
117
}
118

Don Gagne's avatar
Don Gagne committed
119
/// @brief Returns the state machine entry for the specified state.
Don Gagne's avatar
Don Gagne committed
120
const RadioComponentController::stateMachineEntry* RadioComponentController::_getStateMachineEntry(int step) const
Don Gagne's avatar
Don Gagne committed
121
{
122
    static const char* msgBeginPX4 =        QT_TR_NOOP("Lower the Throttle stick all the way down as shown in diagram.\n\n"
Don Gagne's avatar
Don Gagne committed
123
                                            "It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n"
124 125
                                            "Click Next to continue");
    static const char* msgBeginAPM =        QT_TR_NOOP("Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n"
Don Gagne's avatar
Don Gagne committed
126
                                            "Please ensure all motor power is disconnected AND all props are removed from the vehicle.\n\n"
127 128 129 130 131 132 133 134 135 136 137 138
                                            "Click Next to continue");
    static const char* msgThrottleUp =      QT_TR_NOOP("Move the Throttle stick all the way up and hold it there...");
    static const char* msgThrottleDown =    QT_TR_NOOP("Move the Throttle stick all the way down and leave it there...");
    static const char* msgYawLeft =         QT_TR_NOOP("Move the Yaw stick all the way to the left and hold it there...");
    static const char* msgYawRight =        QT_TR_NOOP("Move the Yaw stick all the way to the right and hold it there...");
    static const char* msgRollLeft =        QT_TR_NOOP("Move the Roll stick all the way to the left and hold it there...");
    static const char* msgRollRight =       QT_TR_NOOP("Move the Roll stick all the way to the right and hold it there...");
    static const char* msgPitchDown =       QT_TR_NOOP("Move the Pitch stick all the way down and hold it there...");
    static const char* msgPitchUp =         QT_TR_NOOP("Move the Pitch stick all the way up and hold it there...");
    static const char* msgPitchCenter =     QT_TR_NOOP("Allow the Pitch stick to move back to center...");
    static const char* msgSwitchMinMax =    QT_TR_NOOP("Move all the transmitter switches and/or dials back and forth to their extreme positions.");
    static const char* msgComplete =        QT_TR_NOOP("All settings have been captured. Click Next to write the new parameters to your board.");
139

Don Gagne's avatar
Don Gagne committed
140
    static const stateMachineEntry rgStateMachinePX4[] = {
Don Gagne's avatar
Don Gagne committed
141
        //Function
142 143 144 145 146 147 148 149 150 151 152 153
        { 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 },
Don Gagne's avatar
Don Gagne committed
154
    };
155

Don Gagne's avatar
Don Gagne committed
156 157
    static const stateMachineEntry rgStateMachineAPM[] = {
        //Function
158 159 160 161 162 163 164 165 166 167 168 169
        { 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 },
Don Gagne's avatar
Don Gagne committed
170 171 172 173 174 175 176
    };

    bool badStep = false;
    if (step < 0) {
        badStep = true;
    }
    if (_px4Vehicle()) {
177
        if (step >= static_cast<int>(sizeof(rgStateMachinePX4) / sizeof(rgStateMachinePX4[0]))) {
Don Gagne's avatar
Don Gagne committed
178 179 180
            badStep = true;
        }
    } else {
181
        if (step >= static_cast<int>(sizeof(rgStateMachineAPM) / sizeof(rgStateMachineAPM[0]))) {
Don Gagne's avatar
Don Gagne committed
182 183 184 185 186 187 188 189 190
            badStep = true;
        }
    }
    if (badStep) {
        qWarning() << "Bad step value" << step;
        step = 0;
    }

    const stateMachineEntry* stateMachine = _px4Vehicle() ? rgStateMachinePX4 : rgStateMachineAPM;
191

Don Gagne's avatar
Don Gagne committed
192
    return &stateMachine[step];
Don Gagne's avatar
Don Gagne committed
193
}
194

Don Gagne's avatar
Don Gagne committed
195
void RadioComponentController::_advanceState(void)
Don Gagne's avatar
Don Gagne committed
196 197 198 199 200 201 202
{
    _currentStep++;
    _setupCurrentState();
}


/// @brief Sets up the state machine according to the current step from _currentStep.
Don Gagne's avatar
Don Gagne committed
203
void RadioComponentController::_setupCurrentState(void)
Don Gagne's avatar
Don Gagne committed
204
{
205
    static const char* msgBeginAPMRover = QT_TR_NOOP("Center the Throttle stick as shown in diagram.\nReset all transmitter trims to center.\n\n"
Don Gagne's avatar
Don Gagne committed
206
                                          "Please ensure all motor power is disconnected from the vehicle.\n\n"
207
                                          "Click Next to continue");
Don Gagne's avatar
Don Gagne committed
208 209 210 211 212 213 214 215 216 217 218
    const stateMachineEntry* state = _getStateMachineEntry(_currentStep);

    const char* instructions = state->instructions;
    const char* helpImage = state->image;
    if (_vehicle->rover() && _currentStep == 0) {
        // Hack in center throttle start for Rover. This is to set the correct centered trim for throttle.
        instructions = msgBeginAPMRover;
        helpImage = _imageCenter;
    }
    _statusText->setProperty("text", instructions);
    _setHelpImage(helpImage);
219

Don Gagne's avatar
Don Gagne committed
220
    _stickDetectChannel = _chanMax();
Don Gagne's avatar
Don Gagne committed
221
    _stickDetectSettleStarted = false;
222

Don Gagne's avatar
Don Gagne committed
223
    _rcCalSaveCurrentValues();
224 225 226

    _nextButton->setEnabled(state->nextFn != nullptr);
    _skipButton->setEnabled(state->skipFn != nullptr);
Don Gagne's avatar
Don Gagne committed
227 228
}

Don Gagne's avatar
Don Gagne committed
229 230
/// Connected to Vehicle::rcChannelsChanged signal
void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
Don Gagne's avatar
Don Gagne committed
231
{
Don Gagne's avatar
Don Gagne committed
232 233 234 235 236 237
    int maxChannel = std::min(channelCount, _chanMax());

    for (int channel=0; channel<maxChannel; channel++) {
        int channelValue = pwmValues[channel];

        if (channelValue != -1) {
238
            qCDebug(RadioComponentControllerVerboseLog) << "Raw value" << channel << channelValue;
Don Gagne's avatar
Don Gagne committed
239 240 241 242 243 244 245

            _rcRawValue[channel] = channelValue;
            emit channelRCValueChanged(channel, channelValue);

            // Signal attitude rc values to Qml if mapped
            if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
                switch (_rgChannelInfo[channel].function) {
Don Gagne's avatar
Don Gagne committed
246
                case rcCalFunctionRoll:
Don Gagne's avatar
Don Gagne committed
247
                    emit rollChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
248 249
                    break;
                case rcCalFunctionPitch:
Don Gagne's avatar
Don Gagne committed
250
                    emit pitchChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
251 252
                    break;
                case rcCalFunctionYaw:
Don Gagne's avatar
Don Gagne committed
253
                    emit yawChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
254 255
                    break;
                case rcCalFunctionThrottle:
Don Gagne's avatar
Don Gagne committed
256
                    emit throttleChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
257 258 259 260
                    break;
                default:
                    break;

Don Gagne's avatar
Don Gagne committed
261
                }
Don Gagne's avatar
Don Gagne committed
262
            }
Don Gagne's avatar
Don Gagne committed
263 264 265 266 267 268 269 270

            if (_currentStep == -1) {
                if (_chanCount != channelCount) {
                    _chanCount = channelCount;
                    emit channelCountChanged(_chanCount);
                }
            } else {
                const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
271 272 273 274 275
                if (state) {
                    if (state->rcInputFn) {
                        (this->*state->rcInputFn)(state->function, channel, channelValue);
                    }
                } else {
276
                    qWarning() << "Internal error: nullptr _getStateMachineEntry return";
Don Gagne's avatar
Don Gagne committed
277
                }
Don Gagne's avatar
Don Gagne committed
278
            }
Don Gagne's avatar
Don Gagne committed
279 280 281 282
        }
    }
}

Don Gagne's avatar
Don Gagne committed
283
void RadioComponentController::nextButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
284 285 286 287 288 289 290
{
    if (_currentStep == -1) {
        // Need to have enough channels
        if (_chanCount < _chanMinimum) {
            if (_unitTestMode) {
                emit nextButtonMessageBoxDisplayed();
            } else {
291
                qgcApp()->showMessage(QString("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum));
Don Gagne's avatar
Don Gagne committed
292 293 294 295 296 297
            }
            return;
        }
        _startCalibration();
    } else {
        const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
298 299 300
        if (state && state->nextFn) {
            (this->*state->nextFn)();
        } else {
301
            qWarning() << "Internal error: nullptr _getStateMachineEntry return";
302
        }
Don Gagne's avatar
Don Gagne committed
303 304 305
    }
}

Don Gagne's avatar
Don Gagne committed
306
void RadioComponentController::skipButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
307
{
308 309 310 311
    if (_currentStep == -1) {
        qWarning() << "Internal error: _currentStep == -1";
        return;
    }
312

Don Gagne's avatar
Don Gagne committed
313
    const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
314 315 316
    if (state && state->skipFn) {
        (this->*state->skipFn)();
    } else {
317
        qWarning() << "Internal error: nullptr _getStateMachineEntry return";
318
    }
Don Gagne's avatar
Don Gagne committed
319 320
}

Don Gagne's avatar
Don Gagne committed
321
void RadioComponentController::cancelButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
322
{
Don Gagne's avatar
Don Gagne committed
323
    _stopCalibration();
Don Gagne's avatar
Don Gagne committed
324 325
}

Don Gagne's avatar
Don Gagne committed
326
void RadioComponentController::_saveAllTrims(void)
Don Gagne's avatar
Don Gagne committed
327 328 329 330 331
{
    // 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.
332

Don Gagne's avatar
Don Gagne committed
333
    for (int i=0; i<_chanCount; i++) {
334
        qCDebug(RadioComponentControllerLog) << "_saveAllTrims channel trim" << i<< _rcRawValue[i];
Don Gagne's avatar
Don Gagne committed
335 336
        _rgChannelInfo[i].rcTrim = _rcRawValue[i];
    }
Don Gagne's avatar
Don Gagne committed
337
    _advanceState();
Don Gagne's avatar
Don Gagne committed
338 339 340
}

/// @brief Waits for the sticks to be centered, enabling Next when done.
Don Gagne's avatar
Don Gagne committed
341
void RadioComponentController::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value)
Don Gagne's avatar
Don Gagne committed
342 343 344 345
{
    Q_UNUSED(function);
    Q_UNUSED(chan);
    Q_UNUSED(value);
346

Don Gagne's avatar
Don Gagne committed
347
    // FIXME: Doesn't wait for center
348

Don Gagne's avatar
Don Gagne committed
349
    _nextButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
350 351
}

Don Gagne's avatar
Don Gagne committed
352
bool RadioComponentController::_stickSettleComplete(int value)
Don Gagne's avatar
Don Gagne committed
353 354
{
    // We are waiting for the stick to settle out to a max position
355

Don Gagne's avatar
Don Gagne committed
356 357
    if (abs(_stickDetectValue - value) > _rcCalSettleDelta) {
        // Stick is moving too much to consider stopped
358

Don Gagne's avatar
Don Gagne committed
359
        qCDebug(RadioComponentControllerLog) << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value;
Don Gagne's avatar
Don Gagne committed
360 361 362 363 364

        _stickDetectValue = value;
        _stickDetectSettleStarted = false;
    } else {
        // Stick is still positioned within the specified small range
365

Don Gagne's avatar
Don Gagne committed
366 367
        if (_stickDetectSettleStarted) {
            // We have already started waiting
368

Don Gagne's avatar
Don Gagne committed
369 370 371 372 373 374
            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
375

Don Gagne's avatar
Don Gagne committed
376
            qCDebug(RadioComponentControllerLog) << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value;
377

Don Gagne's avatar
Don Gagne committed
378 379 380 381
            _stickDetectSettleStarted = true;
            _stickDetectSettleElapsed.start();
        }
    }
382

Don Gagne's avatar
Don Gagne committed
383 384 385
    return false;
}

Don Gagne's avatar
Don Gagne committed
386
void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
387
{
Don Gagne's avatar
Don Gagne committed
388
    qCDebug(RadioComponentControllerLog) << "_inputStickDetect function:channel:value" << _functionInfo()[function].parameterName << channel << value;
389

Don Gagne's avatar
Don Gagne committed
390 391 392 393
    // If this channel is already used in a mapping we can't use it again
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
394

Don Gagne's avatar
Don Gagne committed
395
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
396
        // We have not detected enough movement on a channel yet
397

Don Gagne's avatar
Don Gagne committed
398 399
        if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) {
            // Stick has moved far enough to consider it as being selected for the function
400

Don Gagne's avatar
Don Gagne committed
401
            qCDebug(RadioComponentControllerLog) << "_inputStickDetect starting settle wait, function:channel:value" << function << channel << value;
402

Don Gagne's avatar
Don Gagne committed
403 404 405 406 407 408 409 410
            // 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];
411

Don Gagne's avatar
Don Gagne committed
412 413 414 415
            // Stick detection is complete. Stick should be at max position.
            // Map the channel to the function
            _rgFunctionChannelMapping[function] = channel;
            info->function = function;
416

Don Gagne's avatar
Don Gagne committed
417 418
            // Channel should be at max value, if it is below initial set point the the channel is reversed.
            info->reversed = value < _rcValueSave[channel];
419

420 421
            qCDebug(RadioComponentControllerLog) << "_inputStickDetect settle complete, function:channel:value:reversed" << function << channel << value << info->reversed;

Don Gagne's avatar
Don Gagne committed
422 423 424 425 426
            if (info->reversed) {
                _rgChannelInfo[channel].rcMin = value;
            } else {
                _rgChannelInfo[channel].rcMax = value;
            }
427

nanthony21's avatar
nanthony21 committed
428
            _signalAllAttitudeValueChanges();
429

Don Gagne's avatar
Don Gagne committed
430
            _advanceState();
Don Gagne's avatar
Don Gagne committed
431 432 433 434
        }
    }
}

Don Gagne's avatar
Don Gagne committed
435
void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
436 437 438 439 440 441
{
    // We only care about the channel mapped to the function we are working on
    if (_rgFunctionChannelMapping[function] != channel) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
442
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458
        // 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
459

Don Gagne's avatar
Don Gagne committed
460 461
        if (_stickSettleComplete(value)) {
            ChannelInfo* info = &_rgChannelInfo[channel];
462

Don Gagne's avatar
Don Gagne committed
463 464 465 466 467 468
            // Stick detection is complete. Stick should be at min position.
            if (info->reversed) {
                _rgChannelInfo[channel].rcMax = value;
            } else {
                _rgChannelInfo[channel].rcMin = value;
            }
469 470 471 472 473 474 475

            // Check if this is throttle and set trim accordingly
            if (function == rcCalFunctionThrottle) {
                _rgChannelInfo[channel].rcTrim = value;
            }
            // XXX to support configs which can reverse they need to check a reverse
            // flag here and not do this.
476

Don Gagne's avatar
Don Gagne committed
477
            _advanceState();
Don Gagne's avatar
Don Gagne committed
478 479 480 481
        }
    }
}

Don Gagne's avatar
Don Gagne committed
482
void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
483 484 485 486 487
{
    // We only care about the channel mapped to the function we are working on
    if (_rgFunctionChannelMapping[function] != channel) {
        return;
    }
488

Don Gagne's avatar
Don Gagne committed
489
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
490
        // Sticks have not yet moved close enough to center
491

Don Gagne's avatar
Don Gagne committed
492 493 494 495 496 497 498 499
        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)) {
Don Gagne's avatar
Don Gagne committed
500
            _advanceState();
Don Gagne's avatar
Don Gagne committed
501 502 503 504 505
        }
    }
}

/// @brief Saves min/max for non-mapped channels
Don Gagne's avatar
Don Gagne committed
506
void RadioComponentController::_inputSwitchMinMax(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
507 508 509 510 511 512 513
{
    Q_UNUSED(function);

    // If the channel is mapped we already have min/max
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
514

Don Gagne's avatar
Don Gagne committed
515 516 517 518
    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);
519

Don Gagne's avatar
Don Gagne committed
520
            qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting min channel:min" << channel << minValue;
521

Don Gagne's avatar
Don Gagne committed
522 523 524
            _rgChannelInfo[channel].rcMin = minValue;
        } else {
            int maxValue = qMax(_rgChannelInfo[channel].rcMax, value);
525

Don Gagne's avatar
Don Gagne committed
526
            qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue;
527

Don Gagne's avatar
Don Gagne committed
528 529 530 531 532
            _rgChannelInfo[channel].rcMax = maxValue;
        }
    }
}

Don Gagne's avatar
Don Gagne committed
533
void RadioComponentController::_switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep)
Don Gagne's avatar
Don Gagne committed
534 535 536 537 538
{
    // If this channel is already used in a mapping we can't use it again
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
539

Don Gagne's avatar
Don Gagne committed
540 541
    if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) {
        ChannelInfo* info = &_rgChannelInfo[channel];
542

Don Gagne's avatar
Don Gagne committed
543
        // Switch has moved far enough to consider it as being selected for the function
544

Don Gagne's avatar
Don Gagne committed
545 546 547 548
        // Map the channel to the function
        _rgChannelInfo[channel].function = function;
        _rgFunctionChannelMapping[function] = channel;
        info->function = function;
549

Don Gagne's avatar
Don Gagne committed
550
        qCDebug(RadioComponentControllerLog) << "Function:" << function << "mapped to:" << channel;
551

Don Gagne's avatar
Don Gagne committed
552
        if (moveToNextStep) {
Don Gagne's avatar
Don Gagne committed
553
            _advanceState();
Don Gagne's avatar
Don Gagne committed
554 555 556 557
        }
    }
}

Don Gagne's avatar
Don Gagne committed
558
void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
559 560 561 562
{
    _switchDetect(function, channel, value, true /* move to next step after detection */);
}

563
/// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence.
Don Gagne's avatar
Don Gagne committed
564
void RadioComponentController::_resetInternalCalibrationValues(void)
565 566
{
    // Set all raw channels to not reversed and center point values
Don Gagne's avatar
Don Gagne committed
567
    for (int i=0; i<_chanMax(); i++) {
568 569 570
        struct ChannelInfo* info = &_rgChannelInfo[i];
        info->function = rcCalFunctionMax;
        info->reversed = false;
Don Gagne's avatar
Don Gagne committed
571 572 573
        info->rcMin = RadioComponentController::_rcCalPWMCenterPoint;
        info->rcMax = RadioComponentController::_rcCalPWMCenterPoint;
        info->rcTrim = RadioComponentController::_rcCalPWMCenterPoint;
574
    }
575

576
    // Initialize attitude function mapping to function channel not set
577
    for (size_t i=0; i<rcCalFunctionMax; i++) {
Don Gagne's avatar
Don Gagne committed
578
        _rgFunctionChannelMapping[i] = _chanMax();
579
    }
580

nanthony21's avatar
nanthony21 committed
581
    _signalAllAttitudeValueChanges();
Don Gagne's avatar
Don Gagne committed
582 583
}

Don Gagne's avatar
Don Gagne committed
584
/// @brief Sets internal calibration values from the stored parameters
Don Gagne's avatar
Don Gagne committed
585
void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
Don Gagne's avatar
Don Gagne committed
586
{
587
    // Initialize all function mappings to not set
588

Don Gagne's avatar
Don Gagne committed
589
    for (int i=0; i<_chanMax(); i++) {
590 591 592
        struct ChannelInfo* info = &_rgChannelInfo[i];
        info->function = rcCalFunctionMax;
    }
593

594
    for (size_t i=0; i<rcCalFunctionMax; i++) {
Don Gagne's avatar
Don Gagne committed
595
        _rgFunctionChannelMapping[i] = _chanMax();
596
    }
597

598
    // Pull parameters and update
599

600 601 602
    QString minTpl("RC%1_MIN");
    QString maxTpl("RC%1_MAX");
    QString trimTpl("RC%1_TRIM");
603

Don Gagne's avatar
Don Gagne committed
604
    for (int i = 0; i < _chanMax(); ++i) {
605
        struct ChannelInfo* info = &_rgChannelInfo[i];
606 607 608 609 610 611 612 613 614 615 616

        if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(i+1)) {
            if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(i+1))) {
                // Parameter is missing from this version of APM
                info->rcTrim = 1500;
                info->rcMin = 1100;
                info->rcMax = 1900;
                info->reversed = false;
                continue;
            }
        }
617

618 619
        Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1));
        if (paramFact) {
620
            info->rcTrim = paramFact->rawValue().toInt();
621
        }
622

623 624
        paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1));
        if (paramFact) {
625
            info->rcMin = paramFact->rawValue().toInt();
626
        }
Don Gagne's avatar
Don Gagne committed
627

628 629
        paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1));
        if (paramFact) {
630
            info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt();
631
        }
Don Gagne's avatar
Don Gagne committed
632

633
        info->reversed = _channelReversedParamValue(i);
634
    }
635

636 637
    for (int i=0; i<rcCalFunctionMax; i++) {
        int32_t paramChannel;
638

Don Gagne's avatar
Don Gagne committed
639 640
        const char* paramName = _functionInfo()[i].parameterName;
        if (paramName) {
641 642
            Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, paramName);
            if (paramFact) {
643
                paramChannel = paramFact->rawValue().toInt();
644

645
                if (paramChannel > 0 && paramChannel <= _chanMax()) {
646
                    _rgFunctionChannelMapping[i] = paramChannel - 1;
647
                    _rgChannelInfo[paramChannel - 1].function = static_cast<rcCalFunctions>(i);
648
                }
Don Gagne's avatar
Don Gagne committed
649
            }
Don Gagne's avatar
Don Gagne committed
650 651
        }
    }
652

nanthony21's avatar
nanthony21 committed
653
    _signalAllAttitudeValueChanges();
654 655
}

Don Gagne's avatar
Don Gagne committed
656
void RadioComponentController::spektrumBindMode(int mode)
Don Gagne's avatar
Don Gagne committed
657
{
Don Gagne's avatar
Don Gagne committed
658
    _uas->pairRX(0, mode);
659 660
}

Don Gagne's avatar
Don Gagne committed
661
/// @brief Validates the current settings against the calibration rules resetting values as necessary.
Don Gagne's avatar
Don Gagne committed
662
void RadioComponentController::_validateCalibration(void)
Don Gagne's avatar
Don Gagne committed
663
{
Don Gagne's avatar
Don Gagne committed
664
    for (int chan = 0; chan<_chanMax(); chan++) {
Don Gagne's avatar
Don Gagne committed
665
        struct ChannelInfo* info = &_rgChannelInfo[chan];
666

Don Gagne's avatar
Don Gagne committed
667 668 669 670
        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.
            if (info->rcMin > _rcCalPWMValidMinValue || info->rcMax < _rcCalPWMValidMaxValue) {
Don Gagne's avatar
Don Gagne committed
671
                qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting channel" << chan;
Don Gagne's avatar
Don Gagne committed
672 673
                info->rcMin = _rcCalPWMDefaultMinValue;
                info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
674 675 676
                info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
            } else {
                switch (_rgChannelInfo[chan].function) {
677 678 679 680 681 682 683 684 685 686 687 688 689 690 691
                case rcCalFunctionThrottle:
                case rcCalFunctionYaw:
                case rcCalFunctionRoll:
                case rcCalFunctionPitch:
                    // Make sure trim is within min/max
                    if (info->rcTrim < info->rcMin) {
                        info->rcTrim = info->rcMin;
                    } else if (info->rcTrim > info->rcMax) {
                        info->rcTrim = info->rcMax;
                    }
                    break;
                default:
                    // Non-attitude control channels have calculated trim
                    info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
                    break;
Don Gagne's avatar
Don Gagne committed
692
                }
693

Don Gagne's avatar
Don Gagne committed
694 695 696
            }
        } else {
            // Unavailable channels are set to defaults
Don Gagne's avatar
Don Gagne committed
697
            qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting unavailable channel" << chan;
Don Gagne's avatar
Don Gagne committed
698 699
            info->rcMin = _rcCalPWMDefaultMinValue;
            info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
700
            info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
Don Gagne's avatar
Don Gagne committed
701 702 703 704 705 706
            info->reversed = false;
        }
    }
}


707
/// @brief Saves the rc calibration values to the board parameters.
Don Gagne's avatar
Don Gagne committed
708
void RadioComponentController::_writeCalibration(void)
709
{
710
    if (!_uas) return;
711

712 713 714
    if (_px4Vehicle()) {
        _uas->stopCalibration();
    }
715

Don Gagne's avatar
Don Gagne committed
716
    if (!_px4Vehicle() && (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER || _vehicle->multiRotor()) &&  _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed) {
717 718 719 720 721
        // A reversed throttle could lead to dangerous power up issues if the firmware doesn't handle it absolutely correctly in all places.
        // So in this case fail the calibration for anything other than PX4 which is known to be able to handle this correctly.
        emit throttleReversedCalFailure();
    } else {
        _validateCalibration();
722

723 724 725 726 727 728 729 730 731 732 733 734
        QString minTpl("RC%1_MIN");
        QString maxTpl("RC%1_MAX");
        QString trimTpl("RC%1_TRIM");

        // Note that the rc parameters are all float, so you must cast to float in order to get the right QVariant
        for (int chan = 0; chan<_chanMax(); chan++) {
            struct ChannelInfo* info = &_rgChannelInfo[chan];
            int                 oneBasedChannel = chan + 1;

            if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(chan+1) && !parameterExists(FactSystem::defaultComponentId, minTpl.arg(chan+1))) {
                // RC parameters for this channel are missing from this version of APM
                continue;
735
            }
736 737

            Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel));
738
            if (paramFact) {
739
                paramFact->setRawValue(static_cast<float>(info->rcTrim));
740 741 742
            }
            paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel));
            if (paramFact) {
743
                paramFact->setRawValue(static_cast<float>(info->rcMin));
744 745 746
            }
            paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel));
            if (paramFact) {
747
                paramFact->setRawValue(static_cast<float>(info->rcMax));
748
            }
Don Gagne's avatar
Don Gagne committed
749

750
            // For multi-rotor we can determine reverse setting during radio cal. For anything other than multi-rotor, servo installation
Don Gagne's avatar
Don Gagne committed
751 752
            // may affect channel reversing so we can't automatically determine it. This is ok for PX4 given how it uses mixers, but not for ArduPilot.
            if (_vehicle->px4Firmware() || _vehicle->multiRotor()) {
753
                // APM multi-rotor has a backwards interpretation of "reversed" on the Pitch control. So be careful.
754
                bool reversed;
755
                if (_px4Vehicle() || info->function != rcCalFunctionPitch) {
756
                    reversed = info->reversed;
757
                } else {
758
                    reversed = !info->reversed;
759
                }
760
                _setChannelReversedParamValue(chan, reversed);
761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782
            }
        }

        // Write function mapping parameters
        for (size_t i=0; i<rcCalFunctionMax; i++) {
            int32_t paramChannel;
            if (_rgFunctionChannelMapping[i] == _chanMax()) {
                // 0 signals no mapping
                paramChannel = 0;
            } else {
                // Note that the channel value is 1-based
                paramChannel = _rgFunctionChannelMapping[i] + 1;
            }
            const char* paramName = _functionInfo()[i].parameterName;
            if (paramName) {
                Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName);

                if (paramFact && paramFact->rawValue().toInt() != paramChannel) {
                    paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName);
                    if (paramFact) {
                        paramFact->setRawValue(paramChannel);
                    }
783
                }
Don Gagne's avatar
Don Gagne committed
784 785
            }
        }
786
    }
787

Don Gagne's avatar
Don Gagne committed
788 789
    if (_px4Vehicle()) {
        // If the RC_CHAN_COUNT parameter is available write the channel count
Don Gagne's avatar
Don Gagne committed
790 791
        if (parameterExists(FactSystem::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))) {
            getParameterFact(FactSystem::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))->setRawValue(_chanCount);
Don Gagne's avatar
Don Gagne committed
792
        }
793
    }
794

Don Gagne's avatar
Don Gagne committed
795
    _stopCalibration();
796
    _setInternalCalibrationValuesFromParameters();
797 798
}

Don Gagne's avatar
Don Gagne committed
799
/// @brief Starts the calibration process
Don Gagne's avatar
Don Gagne committed
800
void RadioComponentController::_startCalibration(void)
801
{
802 803 804 805
    if (_chanCount < _chanMinimum) {
        qWarning() << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum";
        return;
    }
806

Don Gagne's avatar
Don Gagne committed
807
    _resetInternalCalibrationValues();
808

809
    // Let the mav known we are starting calibration. This should turn off motors and so forth.
810 811 812
    if (_px4Vehicle()) {
        _uas->startCalibration(UASInterface::StartCalibrationRadio);
    }
813

Don Gagne's avatar
Don Gagne committed
814
    _nextButton->setProperty("text", tr("Next"));
Don Gagne's avatar
Don Gagne committed
815
    _cancelButton->setEnabled(true);
816

Don Gagne's avatar
Don Gagne committed
817 818
    _currentStep = 0;
    _setupCurrentState();
819 820
}

Don Gagne's avatar
Don Gagne committed
821
/// @brief Cancels the calibration process, setting things back to initial state.
Don Gagne's avatar
Don Gagne committed
822
void RadioComponentController::_stopCalibration(void)
823
{
Don Gagne's avatar
Don Gagne committed
824
    _currentStep = -1;
825

826
    if (_uas) {
827 828 829
        if (_px4Vehicle()) {
            _uas->stopCalibration();
        }
Don Gagne's avatar
Don Gagne committed
830 831 832
        _setInternalCalibrationValuesFromParameters();
    } else {
        _resetInternalCalibrationValues();
833 834
    }

835 836 837 838 839 840
    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);

841
    _setHelpImage(_imageCenter);
842 843
}

Don Gagne's avatar
Don Gagne committed
844
/// @brief Saves the current channel values, so that we can detect when the use moves an input.
Don Gagne's avatar
Don Gagne committed
845
void RadioComponentController::_rcCalSaveCurrentValues(void)
846
{
Don Gagne's avatar
Don Gagne committed
847
    for (int i = 0; i < _chanMax(); i++) {
Don Gagne's avatar
Don Gagne committed
848
        _rcValueSave[i] = _rcRawValue[i];
849
        qCDebug(RadioComponentControllerLog) << "_rcCalSaveCurrentValues channel:value" << i << _rcValueSave[i];
Don Gagne's avatar
Don Gagne committed
850
    }
851 852 853
}

/// @brief Set up the Save state of calibration.
Don Gagne's avatar
Don Gagne committed
854
void RadioComponentController::_rcCalSave(void)
855 856 857
{
    _rcCalState = rcCalStateSave;

858 859 860 861 862 863 864 865 866
    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);

Don Gagne's avatar
Don Gagne committed
867 868 869
    // 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();
Don Gagne's avatar
Don Gagne committed
870 871
}

Don Gagne's avatar
Don Gagne committed
872
void RadioComponentController::_loadSettings(void)
873 874
{
    QSettings settings;
875

876 877 878
    settings.beginGroup(_settingsGroup);
    _transmitterMode = settings.value(_settingsKeyTransmitterMode, 2).toInt();
    settings.endGroup();
879

880 881 882 883 884
    if (_transmitterMode != 1 || _transmitterMode != 2) {
        _transmitterMode = 2;
    }
}

Don Gagne's avatar
Don Gagne committed
885
void RadioComponentController::_storeSettings(void)
886 887
{
    QSettings settings;
888

889 890 891 892 893
    settings.beginGroup(_settingsGroup);
    settings.setValue(_settingsKeyTransmitterMode, _transmitterMode);
    settings.endGroup();
}

Don Gagne's avatar
Don Gagne committed
894
void RadioComponentController::_setHelpImage(const char* imageFile)
895 896
{
    QString file = _imageFilePrefix;
897

898 899 900 901 902
    if (_transmitterMode == 1) {
        file += _imageFileMode1Dir;
    } else if (_transmitterMode == 2) {
        file += _imageFileMode2Dir;
    } else {
903 904
        qWarning() << "Internal error: Bad _transmitterMode value";
        return;
905 906
    }
    file += imageFile;
907

Don Gagne's avatar
Don Gagne committed
908
    qCDebug(RadioComponentControllerLog) << "_setHelpImage" << file;
909

Don Gagne's avatar
Don Gagne committed
910 911 912 913 914 915 916 917 918 919
    _imageHelp = file;
    emit imageHelpChanged(file);
}

int RadioComponentController::channelCount(void)
{
    return _chanCount;
}

int RadioComponentController::rollChannelRCValue(void)
920
{
Don Gagne's avatar
Don Gagne committed
921
    if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
922 923 924 925 926 927 928 929
        return _rcRawValue[rcCalFunctionRoll];
    } else {
        return 1500;
    }
}

int RadioComponentController::pitchChannelRCValue(void)
{
Don Gagne's avatar
Don Gagne committed
930
    if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
931 932 933 934 935 936 937 938
        return _rcRawValue[rcCalFunctionPitch];
    } else {
        return 1500;
    }
}

int RadioComponentController::yawChannelRCValue(void)
{
Don Gagne's avatar
Don Gagne committed
939
    if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
940 941 942 943 944 945 946 947
        return _rcRawValue[rcCalFunctionYaw];
    } else {
        return 1500;
    }
}

int RadioComponentController::throttleChannelRCValue(void)
{
Don Gagne's avatar
Don Gagne committed
948
    if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
949 950 951 952 953 954 955 956
        return _rcRawValue[rcCalFunctionThrottle];
    } else {
        return 1500;
    }
}

bool RadioComponentController::rollChannelMapped(void)
{
Don Gagne's avatar
Don Gagne committed
957
    return _rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax();
Don Gagne's avatar
Don Gagne committed
958 959 960 961
}

bool RadioComponentController::pitchChannelMapped(void)
{
Don Gagne's avatar
Don Gagne committed
962
    return _rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax();
Don Gagne's avatar
Don Gagne committed
963 964 965 966
}

bool RadioComponentController::yawChannelMapped(void)
{
Don Gagne's avatar
Don Gagne committed
967
    return _rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax();
Don Gagne's avatar
Don Gagne committed
968 969 970 971
}

bool RadioComponentController::throttleChannelMapped(void)
{
Don Gagne's avatar
Don Gagne committed
972
    return _rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax();
Don Gagne's avatar
Don Gagne committed
973 974 975 976
}

bool RadioComponentController::rollChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
977
    if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
978 979 980 981 982 983 984 985
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionRoll]].reversed;
    } else {
        return false;
    }
}

bool RadioComponentController::pitchChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
986
    if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
987 988 989 990 991 992 993 994
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionPitch]].reversed;
    } else {
        return false;
    }
}

bool RadioComponentController::yawChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
995
    if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
996 997 998 999 1000 1001 1002 1003
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionYaw]].reversed;
    } else {
        return false;
    }
}

bool RadioComponentController::throttleChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
1004
    if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed;
    } else {
        return false;
    }
}

void RadioComponentController::setTransmitterMode(int mode)
{
    if (mode == 1 || mode == 2) {
        _transmitterMode = mode;
        if (_currentStep != -1) {
            const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
            _setHelpImage(state->image);
        }
    }
}

nanthony21's avatar
nanthony21 committed
1022
void RadioComponentController::_signalAllAttitudeValueChanges(void)
Don Gagne's avatar
Don Gagne committed
1023 1024 1025 1026 1027
{
    emit rollChannelMappedChanged(rollChannelMapped());
    emit pitchChannelMappedChanged(pitchChannelMapped());
    emit yawChannelMappedChanged(yawChannelMapped());
    emit throttleChannelMappedChanged(throttleChannelMapped());
1028

Don Gagne's avatar
Don Gagne committed
1029 1030 1031 1032
    emit rollChannelReversedChanged(rollChannelReversed());
    emit pitchChannelReversedChanged(pitchChannelReversed());
    emit yawChannelReversedChanged(yawChannelReversed());
    emit throttleChannelReversedChanged(throttleChannelReversed());
1033
}
Don Gagne's avatar
Don Gagne committed
1034 1035 1036

void RadioComponentController::copyTrims(void)
{
1037
    _uas->startCalibration(UASInterface::StartCalibrationCopyTrims);
Don Gagne's avatar
Don Gagne committed
1038
}
Don Gagne's avatar
Don Gagne committed
1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053

bool RadioComponentController::_px4Vehicle(void) const
{
    return _vehicle->firmwareType() == MAV_AUTOPILOT_PX4;
}

const struct RadioComponentController::FunctionInfo* RadioComponentController::_functionInfo(void) const
{
    return _px4Vehicle() ? _rgFunctionInfoPX4 : _rgFunctionInfoAPM;
}

int RadioComponentController::_chanMax(void) const
{
    return _px4Vehicle() ? _chanMaxPX4 : _chanMaxAPM;
}
1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084

bool RadioComponentController::_channelReversedParamValue(int channel)
{
    Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _revParamFormat.arg(channel+1));
    if (paramFact) {
        if (_revParamIsBool) {
            return paramFact->rawValue().toBool();
        } else {
            bool convertOk;
            float floatReversed = paramFact->rawValue().toFloat(&convertOk);
            if (!convertOk) {
                floatReversed = 1.0f;
            }
            return floatReversed == -1.0f;
        }
    }

    return false;
}

void RadioComponentController::_setChannelReversedParamValue(int channel, bool reversed)
{
    Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _revParamFormat.arg(channel+1));
    if (paramFact) {
        if (_revParamIsBool) {
            paramFact->setRawValue(reversed);
        } else {
            paramFact->setRawValue(reversed ? -1.0f : 1.0f);
        }
    }
}