RadioComponentController.cc 43.4 KB
Newer Older
1 2
/****************************************************************************
 *
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

Don Gagne's avatar
Don Gagne committed
101 102 103 104 105
    _resetInternalCalibrationValues();
}

void RadioComponentController::start(void)
{
Don Gagne's avatar
Don Gagne committed
106
    _stopCalibration();
107
    _setInternalCalibrationValuesFromParameters();
Don Gagne's avatar
Don Gagne committed
108
}
109

Don Gagne's avatar
Don Gagne committed
110
RadioComponentController::~RadioComponentController()
Don Gagne's avatar
Don Gagne committed
111
{
112
    _storeSettings();
Don Gagne's avatar
Don Gagne committed
113
}
114

Don Gagne's avatar
Don Gagne committed
115
/// @brief Returns the state machine entry for the specified state.
Don Gagne's avatar
Don Gagne committed
116
const RadioComponentController::stateMachineEntry* RadioComponentController::_getStateMachineEntry(int step) const
Don Gagne's avatar
Don Gagne committed
117
{
118
    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
119
                                            "It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n"
120 121
                                            "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
122
                                            "Please ensure all motor power is disconnected AND all props are removed from the vehicle.\n\n"
123 124 125 126 127 128 129 130 131 132 133 134
                                            "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.");
135

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

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

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

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

Don Gagne's avatar
Don Gagne committed
188
    return &stateMachine[step];
Don Gagne's avatar
Don Gagne committed
189
}
190

Don Gagne's avatar
Don Gagne committed
191
void RadioComponentController::_advanceState(void)
Don Gagne's avatar
Don Gagne committed
192 193 194 195 196 197 198
{
    _currentStep++;
    _setupCurrentState();
}


/// @brief Sets up the state machine according to the current step from _currentStep.
Don Gagne's avatar
Don Gagne committed
199
void RadioComponentController::_setupCurrentState(void)
Don Gagne's avatar
Don Gagne committed
200
{
201
    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
202
                                          "Please ensure all motor power is disconnected from the vehicle.\n\n"
203
                                          "Click Next to continue");
Don Gagne's avatar
Don Gagne committed
204 205 206 207 208 209 210 211 212 213 214
    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);
215 216

    _stickDetectChannel = _chanMax;
Don Gagne's avatar
Don Gagne committed
217
    _stickDetectSettleStarted = false;
218

Don Gagne's avatar
Don Gagne committed
219
    _rcCalSaveCurrentValues();
220 221 222

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

Don Gagne's avatar
Don Gagne committed
225 226
/// Connected to Vehicle::rcChannelsChanged signal
void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
Don Gagne's avatar
Don Gagne committed
227
{
228
    for (int channel=0; channel<channelCount; channel++) {
Don Gagne's avatar
Don Gagne committed
229 230 231
        int channelValue = pwmValues[channel];

        if (channelValue != -1) {
232
            qCDebug(RadioComponentControllerVerboseLog) << "Raw value" << channel << channelValue;
Don Gagne's avatar
Don Gagne committed
233 234 235 236 237 238 239

            _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
240
                case rcCalFunctionRoll:
Don Gagne's avatar
Don Gagne committed
241
                    emit rollChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
242 243
                    break;
                case rcCalFunctionPitch:
Don Gagne's avatar
Don Gagne committed
244
                    emit pitchChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
245 246
                    break;
                case rcCalFunctionYaw:
Don Gagne's avatar
Don Gagne committed
247
                    emit yawChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
248 249
                    break;
                case rcCalFunctionThrottle:
Don Gagne's avatar
Don Gagne committed
250
                    emit throttleChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
251 252 253 254
                    break;
                default:
                    break;

Don Gagne's avatar
Don Gagne committed
255
                }
Don Gagne's avatar
Don Gagne committed
256
            }
Don Gagne's avatar
Don Gagne committed
257 258 259 260 261 262 263 264

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

Don Gagne's avatar
Don Gagne committed
277
void RadioComponentController::nextButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
278 279 280 281 282 283 284
{
    if (_currentStep == -1) {
        // Need to have enough channels
        if (_chanCount < _chanMinimum) {
            if (_unitTestMode) {
                emit nextButtonMessageBoxDisplayed();
            } else {
285
                qgcApp()->showAppMessage(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
286 287 288 289 290 291
            }
            return;
        }
        _startCalibration();
    } else {
        const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
292 293 294
        if (state && state->nextFn) {
            (this->*state->nextFn)();
        } else {
295
            qWarning() << "Internal error: nullptr _getStateMachineEntry return";
296
        }
Don Gagne's avatar
Don Gagne committed
297 298 299
    }
}

Don Gagne's avatar
Don Gagne committed
300
void RadioComponentController::skipButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
301
{
302 303 304 305
    if (_currentStep == -1) {
        qWarning() << "Internal error: _currentStep == -1";
        return;
    }
306

Don Gagne's avatar
Don Gagne committed
307
    const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
308 309 310
    if (state && state->skipFn) {
        (this->*state->skipFn)();
    } else {
311
        qWarning() << "Internal error: nullptr _getStateMachineEntry return";
312
    }
Don Gagne's avatar
Don Gagne committed
313 314
}

Don Gagne's avatar
Don Gagne committed
315
void RadioComponentController::cancelButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
316
{
Don Gagne's avatar
Don Gagne committed
317
    _stopCalibration();
Don Gagne's avatar
Don Gagne committed
318 319
}

Don Gagne's avatar
Don Gagne committed
320
void RadioComponentController::_saveAllTrims(void)
Don Gagne's avatar
Don Gagne committed
321 322 323 324 325
{
    // 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.
326

Don Gagne's avatar
Don Gagne committed
327
    for (int i=0; i<_chanCount; i++) {
328
        qCDebug(RadioComponentControllerLog) << "_saveAllTrims channel trim" << i<< _rcRawValue[i];
Don Gagne's avatar
Don Gagne committed
329 330
        _rgChannelInfo[i].rcTrim = _rcRawValue[i];
    }
Don Gagne's avatar
Don Gagne committed
331
    _advanceState();
Don Gagne's avatar
Don Gagne committed
332 333 334
}

/// @brief Waits for the sticks to be centered, enabling Next when done.
Don Gagne's avatar
Don Gagne committed
335
void RadioComponentController::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value)
Don Gagne's avatar
Don Gagne committed
336 337 338 339
{
    Q_UNUSED(function);
    Q_UNUSED(chan);
    Q_UNUSED(value);
340

Don Gagne's avatar
Don Gagne committed
341
    // FIXME: Doesn't wait for center
342

Don Gagne's avatar
Don Gagne committed
343
    _nextButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
344 345
}

Don Gagne's avatar
Don Gagne committed
346
bool RadioComponentController::_stickSettleComplete(int value)
Don Gagne's avatar
Don Gagne committed
347 348
{
    // We are waiting for the stick to settle out to a max position
349

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

Don Gagne's avatar
Don Gagne committed
353
        qCDebug(RadioComponentControllerLog) << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value;
Don Gagne's avatar
Don Gagne committed
354 355 356 357 358

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

Don Gagne's avatar
Don Gagne committed
360 361
        if (_stickDetectSettleStarted) {
            // We have already started waiting
362

Don Gagne's avatar
Don Gagne committed
363 364 365 366 367 368
            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
369

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

Don Gagne's avatar
Don Gagne committed
372 373 374 375
            _stickDetectSettleStarted = true;
            _stickDetectSettleElapsed.start();
        }
    }
376

Don Gagne's avatar
Don Gagne committed
377 378 379
    return false;
}

Don Gagne's avatar
Don Gagne committed
380
void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
381
{
Don Gagne's avatar
Don Gagne committed
382
    qCDebug(RadioComponentControllerLog) << "_inputStickDetect function:channel:value" << _functionInfo()[function].parameterName << channel << value;
383

Don Gagne's avatar
Don Gagne committed
384 385 386 387
    // If this channel is already used in a mapping we can't use it again
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
388 389

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

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

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

Don Gagne's avatar
Don Gagne committed
397 398 399 400 401 402 403 404
            // 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];
405

Don Gagne's avatar
Don Gagne committed
406 407 408 409
            // Stick detection is complete. Stick should be at max position.
            // Map the channel to the function
            _rgFunctionChannelMapping[function] = channel;
            info->function = function;
410

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

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

Don Gagne's avatar
Don Gagne committed
416 417 418 419 420
            if (info->reversed) {
                _rgChannelInfo[channel].rcMin = value;
            } else {
                _rgChannelInfo[channel].rcMax = value;
            }
421

nanthony21's avatar
nanthony21 committed
422
            _signalAllAttitudeValueChanges();
423

Don Gagne's avatar
Don Gagne committed
424
            _advanceState();
Don Gagne's avatar
Don Gagne committed
425 426 427 428
        }
    }
}

Don Gagne's avatar
Don Gagne committed
429
void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
430 431 432 433 434 435
{
    // We only care about the channel mapped to the function we are working on
    if (_rgFunctionChannelMapping[function] != channel) {
        return;
    }

436
    if (_stickDetectChannel == _chanMax) {
Don Gagne's avatar
Don Gagne committed
437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452
        // 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
453

Don Gagne's avatar
Don Gagne committed
454 455
        if (_stickSettleComplete(value)) {
            ChannelInfo* info = &_rgChannelInfo[channel];
456

Don Gagne's avatar
Don Gagne committed
457 458 459 460 461 462
            // Stick detection is complete. Stick should be at min position.
            if (info->reversed) {
                _rgChannelInfo[channel].rcMax = value;
            } else {
                _rgChannelInfo[channel].rcMin = value;
            }
463 464 465 466 467 468 469

            // 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.
470

Don Gagne's avatar
Don Gagne committed
471
            _advanceState();
Don Gagne's avatar
Don Gagne committed
472 473 474 475
        }
    }
}

Don Gagne's avatar
Don Gagne committed
476
void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
477 478 479 480 481
{
    // We only care about the channel mapped to the function we are working on
    if (_rgFunctionChannelMapping[function] != channel) {
        return;
    }
482 483

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

Don Gagne's avatar
Don Gagne committed
486 487 488 489 490 491 492 493
        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
494
            _advanceState();
Don Gagne's avatar
Don Gagne committed
495 496 497 498 499
        }
    }
}

/// @brief Saves min/max for non-mapped channels
Don Gagne's avatar
Don Gagne committed
500
void RadioComponentController::_inputSwitchMinMax(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
501 502 503 504 505 506 507
{
    Q_UNUSED(function);

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

Don Gagne's avatar
Don Gagne committed
509 510 511 512
    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);
513

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

Don Gagne's avatar
Don Gagne committed
516 517 518
            _rgChannelInfo[channel].rcMin = minValue;
        } else {
            int maxValue = qMax(_rgChannelInfo[channel].rcMax, value);
519

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

Don Gagne's avatar
Don Gagne committed
522 523 524 525 526
            _rgChannelInfo[channel].rcMax = maxValue;
        }
    }
}

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

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

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

Don Gagne's avatar
Don Gagne committed
539 540 541 542
        // Map the channel to the function
        _rgChannelInfo[channel].function = function;
        _rgFunctionChannelMapping[function] = channel;
        info->function = function;
543

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

Don Gagne's avatar
Don Gagne committed
546
        if (moveToNextStep) {
Don Gagne's avatar
Don Gagne committed
547
            _advanceState();
Don Gagne's avatar
Don Gagne committed
548 549 550 551
        }
    }
}

Don Gagne's avatar
Don Gagne committed
552
void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
553 554 555 556
{
    _switchDetect(function, channel, value, true /* move to next step after detection */);
}

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

570
    // Initialize attitude function mapping to function channel not set
571
    for (size_t i=0; i<rcCalFunctionMax; i++) {
572
        _rgFunctionChannelMapping[i] = _chanMax;
573
    }
574

nanthony21's avatar
nanthony21 committed
575
    _signalAllAttitudeValueChanges();
Don Gagne's avatar
Don Gagne committed
576 577
}

Don Gagne's avatar
Don Gagne committed
578
/// @brief Sets internal calibration values from the stored parameters
Don Gagne's avatar
Don Gagne committed
579
void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
Don Gagne's avatar
Don Gagne committed
580
{
581
    // Initialize all function mappings to not set
582 583

    for (int i=0; i<_chanMax; i++) {
584 585 586
        struct ChannelInfo* info = &_rgChannelInfo[i];
        info->function = rcCalFunctionMax;
    }
587

588
    for (size_t i=0; i<rcCalFunctionMax; i++) {
589
        _rgFunctionChannelMapping[i] = _chanMax;
590
    }
591

592
    // Pull parameters and update
593

594 595 596
    QString minTpl("RC%1_MIN");
    QString maxTpl("RC%1_MAX");
    QString trimTpl("RC%1_TRIM");
597 598

    for (int i = 0; i < _chanMax; ++i) {
599
        struct ChannelInfo* info = &_rgChannelInfo[i];
600

601 602 603 604 605 606
        if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(i+1))) {
            info->rcTrim = 1500;
            info->rcMin = 1100;
            info->rcMax = 1900;
            info->reversed = false;
            continue;
607
        }
608

609 610
        Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1));
        if (paramFact) {
611
            info->rcTrim = paramFact->rawValue().toInt();
612
        }
613

614 615
        paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1));
        if (paramFact) {
616
            info->rcMin = paramFact->rawValue().toInt();
617
        }
Don Gagne's avatar
Don Gagne committed
618

619 620
        paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1));
        if (paramFact) {
621
            info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt();
622
        }
Don Gagne's avatar
Don Gagne committed
623

624
        info->reversed = _channelReversedParamValue(i);
625
    }
626

627 628
    for (int i=0; i<rcCalFunctionMax; i++) {
        int32_t paramChannel;
629

Don Gagne's avatar
Don Gagne committed
630 631
        const char* paramName = _functionInfo()[i].parameterName;
        if (paramName) {
632 633
            Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, paramName);
            if (paramFact) {
634
                paramChannel = paramFact->rawValue().toInt();
635

636
                if (paramChannel > 0 && paramChannel <= _chanMax) {
637
                    _rgFunctionChannelMapping[i] = paramChannel - 1;
638
                    _rgChannelInfo[paramChannel - 1].function = static_cast<rcCalFunctions>(i);
639
                }
Don Gagne's avatar
Don Gagne committed
640
            }
Don Gagne's avatar
Don Gagne committed
641 642
        }
    }
643

nanthony21's avatar
nanthony21 committed
644
    _signalAllAttitudeValueChanges();
645 646
}

Don Gagne's avatar
Don Gagne committed
647
void RadioComponentController::spektrumBindMode(int mode)
Don Gagne's avatar
Don Gagne committed
648
{
Don Gagne's avatar
Don Gagne committed
649
    _uas->pairRX(0, mode);
650 651
}

Don Gagne's avatar
Don Gagne committed
652
/// @brief Validates the current settings against the calibration rules resetting values as necessary.
Don Gagne's avatar
Don Gagne committed
653
void RadioComponentController::_validateCalibration(void)
Don Gagne's avatar
Don Gagne committed
654
{
655
    for (int chan = 0; chan<_chanMax; chan++) {
Don Gagne's avatar
Don Gagne committed
656
        struct ChannelInfo* info = &_rgChannelInfo[chan];
657

Don Gagne's avatar
Don Gagne committed
658 659 660 661
        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
662
                qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting channel" << chan;
Don Gagne's avatar
Don Gagne committed
663 664
                info->rcMin = _rcCalPWMDefaultMinValue;
                info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
665 666 667
                info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
            } else {
                switch (_rgChannelInfo[chan].function) {
668 669 670 671 672 673 674 675 676 677 678 679 680 681 682
                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
683
                }
684

Don Gagne's avatar
Don Gagne committed
685 686 687
            }
        } else {
            // Unavailable channels are set to defaults
Don Gagne's avatar
Don Gagne committed
688
            qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting unavailable channel" << chan;
Don Gagne's avatar
Don Gagne committed
689 690
            info->rcMin = _rcCalPWMDefaultMinValue;
            info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
691
            info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
Don Gagne's avatar
Don Gagne committed
692 693 694 695 696 697
            info->reversed = false;
        }
    }
}


698
/// @brief Saves the rc calibration values to the board parameters.
Don Gagne's avatar
Don Gagne committed
699
void RadioComponentController::_writeCalibration(void)
700
{
701
    if (!_uas) return;
702

703
    if (_px4Vehicle()) {
704
        _vehicle->stopCalibration();
705
    }
706

Don Gagne's avatar
Don Gagne committed
707
    if (!_px4Vehicle() && (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER || _vehicle->multiRotor()) &&  _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed) {
708 709 710 711 712
        // 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();
713

714 715 716 717 718
        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
719
        for (int chan = 0; chan<_chanMax; chan++) {
720 721 722
            struct ChannelInfo* info = &_rgChannelInfo[chan];
            int                 oneBasedChannel = chan + 1;

723
            if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(chan+1))) {
724
                continue;
725
            }
726 727

            Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel));
728
            if (paramFact) {
729
                paramFact->setRawValue(static_cast<float>(info->rcTrim));
730 731 732
            }
            paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel));
            if (paramFact) {
733
                paramFact->setRawValue(static_cast<float>(info->rcMin));
734 735 736
            }
            paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel));
            if (paramFact) {
737
                paramFact->setRawValue(static_cast<float>(info->rcMax));
738
            }
Don Gagne's avatar
Don Gagne committed
739

740
            // 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
741 742
            // 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()) {
743
                // APM multi-rotor has a backwards interpretation of "reversed" on the Pitch control. So be careful.
744
                bool reversed;
745
                if (_px4Vehicle() || info->function != rcCalFunctionPitch) {
746
                    reversed = info->reversed;
747
                } else {
748
                    reversed = !info->reversed;
749
                }
750
                _setChannelReversedParamValue(chan, reversed);
751 752 753 754 755 756
            }
        }

        // Write function mapping parameters
        for (size_t i=0; i<rcCalFunctionMax; i++) {
            int32_t paramChannel;
757
            if (_rgFunctionChannelMapping[i] == _chanMax) {
758 759 760 761 762 763 764 765 766 767 768 769 770 771 772
                // 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);
                    }
773
                }
Don Gagne's avatar
Don Gagne committed
774 775
            }
        }
776
    }
777

Don Gagne's avatar
Don Gagne committed
778 779
    if (_px4Vehicle()) {
        // If the RC_CHAN_COUNT parameter is available write the channel count
Don Gagne's avatar
Don Gagne committed
780 781
        if (parameterExists(FactSystem::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))) {
            getParameterFact(FactSystem::defaultComponentId, QStringLiteral("RC_CHAN_CNT"))->setRawValue(_chanCount);
Don Gagne's avatar
Don Gagne committed
782
        }
783
    }
784

Don Gagne's avatar
Don Gagne committed
785
    _stopCalibration();
786
    _setInternalCalibrationValuesFromParameters();
787 788
}

Don Gagne's avatar
Don Gagne committed
789
/// @brief Starts the calibration process
Don Gagne's avatar
Don Gagne committed
790
void RadioComponentController::_startCalibration(void)
791
{
792 793 794 795
    if (_chanCount < _chanMinimum) {
        qWarning() << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum";
        return;
    }
796

Don Gagne's avatar
Don Gagne committed
797
    _resetInternalCalibrationValues();
798

799
    // Let the mav known we are starting calibration. This should turn off motors and so forth.
800
    if (_px4Vehicle()) {
801
        _vehicle->startCalibration(Vehicle::CalibrationRadio);
802
    }
803

Don Gagne's avatar
Don Gagne committed
804
    _nextButton->setProperty("text", tr("Next"));
Don Gagne's avatar
Don Gagne committed
805
    _cancelButton->setEnabled(true);
806

Don Gagne's avatar
Don Gagne committed
807 808
    _currentStep = 0;
    _setupCurrentState();
809 810
}

Don Gagne's avatar
Don Gagne committed
811
/// @brief Cancels the calibration process, setting things back to initial state.
Don Gagne's avatar
Don Gagne committed
812
void RadioComponentController::_stopCalibration(void)
813
{
Don Gagne's avatar
Don Gagne committed
814
    _currentStep = -1;
815

816
    if (_uas) {
817
        if (_px4Vehicle()) {
818
            _vehicle->stopCalibration();
819
        }
Don Gagne's avatar
Don Gagne committed
820 821 822
        _setInternalCalibrationValuesFromParameters();
    } else {
        _resetInternalCalibrationValues();
823 824
    }

825 826 827 828 829 830
    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);

831
    _setHelpImage(_imageCenter);
832 833
}

Don Gagne's avatar
Don Gagne committed
834
/// @brief Saves the current channel values, so that we can detect when the use moves an input.
Don Gagne's avatar
Don Gagne committed
835
void RadioComponentController::_rcCalSaveCurrentValues(void)
836
{
837
    for (int i = 0; i < _chanMax; i++) {
Don Gagne's avatar
Don Gagne committed
838
        _rcValueSave[i] = _rcRawValue[i];
839
        qCDebug(RadioComponentControllerLog) << "_rcCalSaveCurrentValues channel:value" << i << _rcValueSave[i];
Don Gagne's avatar
Don Gagne committed
840
    }
841 842 843
}

/// @brief Set up the Save state of calibration.
Don Gagne's avatar
Don Gagne committed
844
void RadioComponentController::_rcCalSave(void)
845 846 847
{
    _rcCalState = rcCalStateSave;

848 849 850 851 852 853 854 855 856
    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
857 858 859
    // 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
860 861
}

Don Gagne's avatar
Don Gagne committed
862
void RadioComponentController::_loadSettings(void)
863 864
{
    QSettings settings;
865

866 867 868
    settings.beginGroup(_settingsGroup);
    _transmitterMode = settings.value(_settingsKeyTransmitterMode, 2).toInt();
    settings.endGroup();
869 870

    if (!(_transmitterMode == 1 || _transmitterMode == 2)) {
871 872 873 874
        _transmitterMode = 2;
    }
}

Don Gagne's avatar
Don Gagne committed
875
void RadioComponentController::_storeSettings(void)
876 877
{
    QSettings settings;
878

879 880 881 882 883
    settings.beginGroup(_settingsGroup);
    settings.setValue(_settingsKeyTransmitterMode, _transmitterMode);
    settings.endGroup();
}

Don Gagne's avatar
Don Gagne committed
884
void RadioComponentController::_setHelpImage(const char* imageFile)
885 886
{
    QString file = _imageFilePrefix;
887

888 889 890 891 892
    if (_transmitterMode == 1) {
        file += _imageFileMode1Dir;
    } else if (_transmitterMode == 2) {
        file += _imageFileMode2Dir;
    } else {
893 894
        qWarning() << "Internal error: Bad _transmitterMode value";
        return;
895 896
    }
    file += imageFile;
897

Don Gagne's avatar
Don Gagne committed
898
    qCDebug(RadioComponentControllerLog) << "_setHelpImage" << file;
899

Don Gagne's avatar
Don Gagne committed
900 901 902 903 904 905 906 907 908 909
    _imageHelp = file;
    emit imageHelpChanged(file);
}

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

int RadioComponentController::rollChannelRCValue(void)
910 911
{
    if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) {
Don Gagne's avatar
Don Gagne committed
912 913 914 915 916 917 918 919
        return _rcRawValue[rcCalFunctionRoll];
    } else {
        return 1500;
    }
}

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

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

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

bool RadioComponentController::rollChannelMapped(void)
{
947
    return _rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax;
Don Gagne's avatar
Don Gagne committed
948 949 950 951
}

bool RadioComponentController::pitchChannelMapped(void)
{
952
    return _rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax;
Don Gagne's avatar
Don Gagne committed
953 954 955 956
}

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

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

bool RadioComponentController::rollChannelReversed(void)
{
967
    if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) {
Don Gagne's avatar
Don Gagne committed
968 969 970 971 972 973 974 975
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionRoll]].reversed;
    } else {
        return false;
    }
}

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

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

bool RadioComponentController::throttleChannelReversed(void)
{
994
    if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) {
Don Gagne's avatar
Don Gagne committed
995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011
        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
1012
void RadioComponentController::_signalAllAttitudeValueChanges(void)
Don Gagne's avatar
Don Gagne committed
1013 1014 1015 1016 1017
{
    emit rollChannelMappedChanged(rollChannelMapped());
    emit pitchChannelMappedChanged(pitchChannelMapped());
    emit yawChannelMappedChanged(yawChannelMapped());
    emit throttleChannelMappedChanged(throttleChannelMapped());
1018

Don Gagne's avatar
Don Gagne committed
1019 1020 1021 1022
    emit rollChannelReversedChanged(rollChannelReversed());
    emit pitchChannelReversedChanged(pitchChannelReversed());
    emit yawChannelReversedChanged(yawChannelReversed());
    emit throttleChannelReversedChanged(throttleChannelReversed());
1023
}
Don Gagne's avatar
Don Gagne committed
1024 1025 1026

void RadioComponentController::copyTrims(void)
{
1027
    _vehicle->startCalibration(Vehicle::CalibrationCopyTrims);
Don Gagne's avatar
Don Gagne committed
1028
}
Don Gagne's avatar
Don Gagne committed
1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039

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

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

1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069
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);
        }
    }
}