RadioComponentController.cc 44.2 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * 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

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

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

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

Don Gagne's avatar
Don Gagne committed
28 29
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;
30 31 32 33 34 35 36 37
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
38 39 40

const int RadioComponentController::_stickDetectSettleMSecs = 500;

41
const char*  RadioComponentController::_imageFilePrefix =   "calibration/";
Don Gagne's avatar
Don Gagne committed
42 43
const char*  RadioComponentController::_imageFileMode1Dir = "mode1/";
const char*  RadioComponentController::_imageFileMode2Dir = "mode2/";
44 45 46
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
47
const char*  RadioComponentController::_imageThrottleDown = "radioThrottleDown.png";
48 49 50 51 52 53
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
54 55
const char*  RadioComponentController::_imageSwitchMinMax = "radioSwitchMinMax.png";

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

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

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

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

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

87 88 89 90 91 92 93 94 95 96
    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
97
    connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged);
98
    _loadSettings();
99 100 101 102

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

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

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

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

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

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

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

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

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

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

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


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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
434
void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
435 436 437 438 439 440
{
    // 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
441
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457
        // 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
458

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

597
    // Pull parameters and update
598

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

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

        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;
            }
        }
616

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

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

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

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

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
666 667 668 669
        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
670
                qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting channel" << chan;
Don Gagne's avatar
Don Gagne committed
671 672
                info->rcMin = _rcCalPWMDefaultMinValue;
                info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
673 674 675
                info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
            } else {
                switch (_rgChannelInfo[chan].function) {
676 677 678 679 680 681 682 683 684 685 686 687 688 689 690
                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
691
                }
692

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


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

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

Don Gagne's avatar
Don Gagne committed
715
    if (!_px4Vehicle() && (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER || _vehicle->multiRotor()) &&  _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed) {
716 717 718 719 720
        // 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();
721

722 723 724 725 726 727 728 729 730 731 732 733
        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;
734
            }
735 736

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

749
            // 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
750 751
            // 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()) {
752
                // APM multi-rotor has a backwards interpretation of "reversed" on the Pitch control. So be careful.
753
                bool reversed;
754
                if (_px4Vehicle() || info->function != rcCalFunctionPitch) {
755
                    reversed = info->reversed;
756
                } else {
757
                    reversed = !info->reversed;
758
                }
759
                _setChannelReversedParamValue(chan, reversed);
760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781
            }
        }

        // 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);
                    }
782
                }
Don Gagne's avatar
Don Gagne committed
783 784
            }
        }
785
    }
786

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

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

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

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

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

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

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

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

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

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

840
    _setHelpImage(_imageCenter);
841 842
}

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

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

857 858 859 860 861 862 863 864 865
    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
866 867 868
    // 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
869 870
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

bool RadioComponentController::throttleChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
1003
    if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020
        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
1021
void RadioComponentController::_signalAllAttitudeValueChanges(void)
Don Gagne's avatar
Don Gagne committed
1022 1023 1024 1025 1026
{
    emit rollChannelMappedChanged(rollChannelMapped());
    emit pitchChannelMappedChanged(pitchChannelMapped());
    emit yawChannelMappedChanged(yawChannelMapped());
    emit throttleChannelMappedChanged(throttleChannelMapped());
1027

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

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

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;
}
1053 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

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);
        }
    }
}