Skip to content
RadioComponentController.cc 44.3 KiB
Newer Older
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/

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

Don Gagne's avatar
Don Gagne committed
#include "RadioComponentController.h"
Don Gagne's avatar
Don Gagne committed
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
#include <QSettings>

QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "RadioComponentControllerLog")
QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "RadioComponentControllerVerboseLog")
#ifdef UNITTEST_BUILD
// Nasty hack to expose controller to unit test code
RadioComponentController* RadioComponentController::_unitTestController = NULL;
#endif

Don Gagne's avatar
Don Gagne committed
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;
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

const int RadioComponentController::_stickDetectSettleMSecs = 500;

const char*  RadioComponentController::_imageFilePrefix =   "calibration/";
Don Gagne's avatar
Don Gagne committed
const char*  RadioComponentController::_imageFileMode1Dir = "mode1/";
const char*  RadioComponentController::_imageFileMode2Dir = "mode2/";
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
const char*  RadioComponentController::_imageThrottleDown = "radioThrottleDown.png";
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
const char*  RadioComponentController::_imageSwitchMinMax = "radioSwitchMinMax.png";

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

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

Don Gagne's avatar
Don Gagne committed
const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfoPX4[RadioComponentController::rcCalFunctionMax] = {
{ "RC_MAP_ROLL" },
{ "RC_MAP_PITCH" },
{ "RC_MAP_YAW" },
{ "RC_MAP_THROTTLE" }
Don Gagne's avatar
Don Gagne committed
const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfoAPM[RadioComponentController::rcCalFunctionMax] = {
{ "RCMAP_ROLL" },
{ "RCMAP_PITCH" },
{ "RCMAP_YAW" },
{ "RCMAP_THROTTLE" }
Don Gagne's avatar
Don Gagne committed
};

RadioComponentController::RadioComponentController(void)
    : _currentStep(-1)
    , _transmitterMode(2)
    , _chanCount(0)
    , _rcCalState(rcCalStateChannelWait)
    , _unitTestMode(false)
    , _statusText(NULL)
    , _cancelButton(NULL)
    , _nextButton(NULL)
    , _skipButton(NULL)
#ifdef UNITTEST_BUILD
    // Nasty hack to expose controller to unit test code
    _unitTestController = this;
#endif

    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
    connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged);
    _loadSettings();

    // 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;
Don Gagne's avatar
Don Gagne committed
    _resetInternalCalibrationValues();
}

void RadioComponentController::start(void)
{
Don Gagne's avatar
Don Gagne committed
    _stopCalibration();
    _setInternalCalibrationValuesFromParameters();
Don Gagne's avatar
Don Gagne committed
}
Don Gagne's avatar
Don Gagne committed
RadioComponentController::~RadioComponentController()
Don Gagne's avatar
Don Gagne committed
{
    _storeSettings();
Don Gagne's avatar
Don Gagne committed
}
Don Gagne's avatar
Don Gagne committed
/// @brief Returns the state machine entry for the specified state.
Don Gagne's avatar
Don Gagne committed
const RadioComponentController::stateMachineEntry* RadioComponentController::_getStateMachineEntry(int step) const
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    static const char* msgBeginPX4 =        "Lower the Throttle stick all the way down as shown in diagram.\n\n"
Don Gagne's avatar
Don Gagne committed
                                            "It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n"
                                            "Click Next to continue";
    static const char* msgBeginAPM =        "Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n"
                                            "Please ensure all motor power is disconnected AND all props are removed from the vehicle.\n\n"
                                            "Click Next to continue";
    static const char* msgThrottleUp =      "Move the Throttle stick all the way up and hold it there...";
    static const char* msgThrottleDown =    "Move the Throttle stick all the way down and leave it there...";
    static const char* msgYawLeft =         "Move the Yaw stick all the way to the left and hold it there...";
    static const char* msgYawRight =        "Move the Yaw stick all the way to the right and hold it there...";
    static const char* msgRollLeft =        "Move the Roll stick all the way to the left and hold it there...";
    static const char* msgRollRight =       "Move the Roll stick all the way to the right and hold it there...";
    static const char* msgPitchDown =       "Move the Pitch stick all the way down and hold it there...";
    static const char* msgPitchUp =         "Move the Pitch stick all the way up and hold it there...";
    static const char* msgPitchCenter =     "Allow the Pitch stick to move back to center...";
    static const char* msgSwitchMinMax =    "Move all the transmitter switches and/or dials back and forth to their extreme positions.";
    static const char* msgComplete =        "All settings have been captured. Click Next to write the new parameters to your board.";
Don Gagne's avatar
Don Gagne committed
    
Don Gagne's avatar
Don Gagne committed
    static const stateMachineEntry rgStateMachinePX4[] = {
Don Gagne's avatar
Don Gagne committed
        //Function
Don Gagne's avatar
Don Gagne committed
        { rcCalFunctionMax,                 msgBeginPX4,        _imageHome,         &RadioComponentController::_inputCenterWaitBegin,   &RadioComponentController::_saveAllTrims,       NULL },
Don Gagne's avatar
Don Gagne committed
        { rcCalFunctionThrottle,            msgThrottleUp,      _imageThrottleUp,   &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionThrottle,            msgThrottleDown,    _imageThrottleDown, &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionYaw,                 msgYawRight,        _imageYawRight,     &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionYaw,                 msgYawLeft,         _imageYawLeft,      &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionRoll,                msgRollRight,       _imageRollRight,    &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionRoll,                msgRollLeft,        _imageRollLeft,     &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionPitch,               msgPitchUp,         _imagePitchUp,      &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionPitch,               msgPitchDown,       _imagePitchDown,    &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionPitch,               msgPitchCenter,     _imageHome,         &RadioComponentController::_inputCenterWait,        NULL,                                           NULL },
        { rcCalFunctionMax,                 msgSwitchMinMax,    _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax,      &RadioComponentController::_advanceState,       NULL },
        { rcCalFunctionMax,                 msgComplete,        _imageThrottleDown, NULL,                                               &RadioComponentController::_writeCalibration,   NULL },
Don Gagne's avatar
Don Gagne committed
    static const stateMachineEntry rgStateMachineAPM[] = {
        //Function
        { rcCalFunctionMax,                 msgBeginAPM,        _imageHome,         &RadioComponentController::_inputCenterWaitBegin,   &RadioComponentController::_saveAllTrims,       NULL },
        { rcCalFunctionThrottle,            msgThrottleUp,      _imageThrottleUp,   &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionThrottle,            msgThrottleDown,    _imageThrottleDown, &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionYaw,                 msgYawRight,        _imageYawRight,     &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionYaw,                 msgYawLeft,         _imageYawLeft,      &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionRoll,                msgRollRight,       _imageRollRight,    &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionRoll,                msgRollLeft,        _imageRollLeft,     &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionPitch,               msgPitchUp,         _imagePitchUp,      &RadioComponentController::_inputStickDetect,       NULL,                                           NULL },
        { rcCalFunctionPitch,               msgPitchDown,       _imagePitchDown,    &RadioComponentController::_inputStickMin,          NULL,                                           NULL },
        { rcCalFunctionPitch,               msgPitchCenter,     _imageHome,         &RadioComponentController::_inputCenterWait,        NULL,                                           NULL },
        { rcCalFunctionMax,                 msgSwitchMinMax,    _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax,      &RadioComponentController::_advanceState,       NULL },
        { rcCalFunctionMax,                 msgComplete,        _imageThrottleDown, NULL,                                               &RadioComponentController::_writeCalibration,   NULL },
    };

    bool badStep = false;
    if (step < 0) {
        badStep = true;
    }
    if (_px4Vehicle()) {
        if (step >= (int)(sizeof(rgStateMachinePX4) / sizeof(rgStateMachinePX4[0]))) {
            badStep = true;
        }
    } else {
        if (step >= (int)(sizeof(rgStateMachineAPM) / sizeof(rgStateMachineAPM[0]))) {
            badStep = true;
        }
    }
    if (badStep) {
        qWarning() << "Bad step value" << step;
        step = 0;
    }

    const stateMachineEntry* stateMachine = _px4Vehicle() ? rgStateMachinePX4 : rgStateMachineAPM;
Don Gagne's avatar
Don Gagne committed
    
Don Gagne's avatar
Don Gagne committed
    return &stateMachine[step];
Don Gagne's avatar
Don Gagne committed
}
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_advanceState(void)
Don Gagne's avatar
Don Gagne committed
{
    _currentStep++;
    _setupCurrentState();
}


/// @brief Sets up the state machine according to the current step from _currentStep.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_setupCurrentState(void)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    static const char* msgBeginAPMRover = "Center the Throttle stick as shown in diagram.\nReset all transmitter trims to center.\n\n"
                                          "Please ensure all motor power is disconnected from the vehicle.\n\n"
                                          "Click Next to continue";
    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);
Don Gagne's avatar
Don Gagne committed
    
Don Gagne's avatar
Don Gagne committed
    _stickDetectChannel = _chanMax();
Don Gagne's avatar
Don Gagne committed
    _stickDetectSettleStarted = false;
    
    _rcCalSaveCurrentValues();
    
Don Gagne's avatar
Don Gagne committed
    _nextButton->setEnabled(state->nextFn != NULL);
    _skipButton->setEnabled(state->skipFn != NULL);
Don Gagne's avatar
Don Gagne committed
/// Connected to Vehicle::rcChannelsChanged signal
void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    int maxChannel = std::min(channelCount, _chanMax());

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

        if (channelValue != -1) {
            qCDebug(RadioComponentControllerVerboseLog) << "Raw value" << channel << channelValue;
Don Gagne's avatar
Don Gagne committed

            _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
                case rcCalFunctionRoll:
Don Gagne's avatar
Don Gagne committed
                    emit rollChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
                    break;
                case rcCalFunctionPitch:
Don Gagne's avatar
Don Gagne committed
                    emit pitchChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
                    break;
                case rcCalFunctionYaw:
Don Gagne's avatar
Don Gagne committed
                    emit yawChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
                    break;
                case rcCalFunctionThrottle:
Don Gagne's avatar
Don Gagne committed
                    emit throttleChannelRCValueChanged(channelValue);
Don Gagne's avatar
Don Gagne committed
                    break;
                default:
                    break;

Don Gagne's avatar
Don Gagne committed
                }
Don Gagne's avatar
Don Gagne committed
            }
Don Gagne's avatar
Don Gagne committed

            if (_currentStep == -1) {
                if (_chanCount != channelCount) {
                    _chanCount = channelCount;
                    emit channelCountChanged(_chanCount);
                }
            } else {
                const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
                if (state) {
                    if (state->rcInputFn) {
                        (this->*state->rcInputFn)(state->function, channel, channelValue);
                    }
                } else {
                    qWarning() << "Internal error: NULL _getStateMachineEntry return";
Don Gagne's avatar
Don Gagne committed
                }
Don Gagne's avatar
Don Gagne committed
            }
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::nextButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
{
    if (_currentStep == -1) {
        // Need to have enough channels
        if (_chanCount < _chanMinimum) {
            if (_unitTestMode) {
                emit nextButtonMessageBoxDisplayed();
            } else {
                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
            }
            return;
        }
        _startCalibration();
    } else {
        const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
        if (state && state->nextFn) {
            (this->*state->nextFn)();
        } else {
            qWarning() << "Internal error: NULL _getStateMachineEntry return";
        }
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::skipButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
{
    if (_currentStep == -1) {
        qWarning() << "Internal error: _currentStep == -1";
        return;
    }
Don Gagne's avatar
Don Gagne committed
    
    const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
    if (state && state->skipFn) {
        (this->*state->skipFn)();
    } else {
        qWarning() << "Internal error: NULL _getStateMachineEntry return";
    }
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::cancelButtonClicked(void)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    _stopCalibration();
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_saveAllTrims(void)
Don Gagne's avatar
Don Gagne committed
{
    // We save all trims as the first step. At this point no channels are mapped but it should still
    // allow us to get good trims for the roll/pitch/yaw/throttle even though we don't know which
    // channels they are yet. AS we continue through the process the other channels will get their
    // trims reset to correct values.
    
    for (int i=0; i<_chanCount; i++) {
        qCDebug(RadioComponentControllerLog) << "_saveAllTrims channel trim" << i<< _rcRawValue[i];
Don Gagne's avatar
Don Gagne committed
        _rgChannelInfo[i].rcTrim = _rcRawValue[i];
    }
Don Gagne's avatar
Don Gagne committed
    _advanceState();
Don Gagne's avatar
Don Gagne committed
}

/// @brief Waits for the sticks to be centered, enabling Next when done.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value)
Don Gagne's avatar
Don Gagne committed
{
    Q_UNUSED(function);
    Q_UNUSED(chan);
    Q_UNUSED(value);
    
    // FIXME: Doesn't wait for center
    
Don Gagne's avatar
Don Gagne committed
    _nextButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
bool RadioComponentController::_stickSettleComplete(int value)
Don Gagne's avatar
Don Gagne committed
{
    // We are waiting for the stick to settle out to a max position
    
    if (abs(_stickDetectValue - value) > _rcCalSettleDelta) {
        // Stick is moving too much to consider stopped
        
Don Gagne's avatar
Don Gagne committed
        qCDebug(RadioComponentControllerLog) << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value;
Don Gagne's avatar
Don Gagne committed

        _stickDetectValue = value;
        _stickDetectSettleStarted = false;
    } else {
        // Stick is still positioned within the specified small range
        
        if (_stickDetectSettleStarted) {
            // We have already started waiting
            
            if (_stickDetectSettleElapsed.elapsed() > _stickDetectSettleMSecs) {
                // Stick has stayed positioned in one place long enough, detection is complete.
                return true;
            }
        } else {
            // Start waiting for the stick to stay settled for _stickDetectSettleWaitMSecs msecs
            
Don Gagne's avatar
Don Gagne committed
            qCDebug(RadioComponentControllerLog) << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value;
Don Gagne's avatar
Don Gagne committed
            
            _stickDetectSettleStarted = true;
            _stickDetectSettleElapsed.start();
        }
    }
    
    return false;
}

Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    qCDebug(RadioComponentControllerLog) << "_inputStickDetect function:channel:value" << _functionInfo()[function].parameterName << channel << value;
Don Gagne's avatar
Don Gagne committed
    
    // If this channel is already used in a mapping we can't use it again
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
Don Gagne's avatar
Don Gagne committed
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        // We have not detected enough movement on a channel yet
        
        if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) {
            // Stick has moved far enough to consider it as being selected for the function
            
Don Gagne's avatar
Don Gagne committed
            qCDebug(RadioComponentControllerLog) << "_inputStickDetect starting settle wait, function:channel:value" << function << channel << value;
Don Gagne's avatar
Don Gagne committed
            
            // 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];
            
            // Stick detection is complete. Stick should be at max position.
            // Map the channel to the function
            _rgFunctionChannelMapping[function] = channel;
            info->function = function;
            
            // Channel should be at max value, if it is below initial set point the the channel is reversed.
            info->reversed = value < _rcValueSave[channel];
            
            qCDebug(RadioComponentControllerLog) << "_inputStickDetect settle complete, function:channel:value:reversed" << function << channel << value << info->reversed;

Don Gagne's avatar
Don Gagne committed
            if (info->reversed) {
                _rgChannelInfo[channel].rcMin = value;
            } else {
                _rgChannelInfo[channel].rcMax = value;
            }
            
nanthony21's avatar
nanthony21 committed
            _signalAllAttitudeValueChanges();
Don Gagne's avatar
Don Gagne committed
            
            _advanceState();
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
{
    // 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
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        // Setup up to detect stick being pegged to extreme position
        if (_rgChannelInfo[channel].reversed) {
            if (value > _rcCalPWMCenterPoint + _rcCalMoveDelta) {
                _stickDetectChannel = channel;
                _stickDetectInitialValue = value;
                _stickDetectValue = value;
            }
        } else {
            if (value < _rcCalPWMCenterPoint - _rcCalMoveDelta) {
                _stickDetectChannel = channel;
                _stickDetectInitialValue = value;
                _stickDetectValue = value;
            }
        }
    } else {
        // We are waiting for the selected channel to settle out
        
        if (_stickSettleComplete(value)) {
            ChannelInfo* info = &_rgChannelInfo[channel];
            
            // Stick detection is complete. Stick should be at min position.
            if (info->reversed) {
                _rgChannelInfo[channel].rcMax = value;
            } else {
                _rgChannelInfo[channel].rcMin = value;
            }

            // 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.
Don Gagne's avatar
Don Gagne committed
            
Don Gagne's avatar
Don Gagne committed
            _advanceState();
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
{
    // 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
    if (_stickDetectChannel == _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        // Sticks have not yet moved close enough to center
        
        if (abs(_rcCalPWMCenterPoint - value) < _rcCalRoughCenterDelta) {
            // Stick has moved close enough to center that we can start waiting for it to settle
            _stickDetectChannel = channel;
            _stickDetectInitialValue = value;
            _stickDetectValue = value;
        }
    } else {
        if (_stickSettleComplete(value)) {
Don Gagne's avatar
Don Gagne committed
            _advanceState();
Don Gagne's avatar
Don Gagne committed
        }
    }
}

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

    // If the channel is mapped we already have min/max
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
    
    if (abs(_rcCalPWMCenterPoint - value) > _rcCalMoveDelta) {
        // Stick has moved far enough from center to consider for min/max
        if (value < _rcCalPWMCenterPoint) {
            int minValue = qMin(_rgChannelInfo[channel].rcMin, value);
            
Don Gagne's avatar
Don Gagne committed
            qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting min channel:min" << channel << minValue;
Don Gagne's avatar
Don Gagne committed
            
            _rgChannelInfo[channel].rcMin = minValue;
        } else {
            int maxValue = qMax(_rgChannelInfo[channel].rcMax, value);
            
Don Gagne's avatar
Don Gagne committed
            qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue;
Don Gagne's avatar
Don Gagne committed
            
            _rgChannelInfo[channel].rcMax = maxValue;
        }
    }
}

Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep)
Don Gagne's avatar
Don Gagne committed
{
    // If this channel is already used in a mapping we can't use it again
    if (_rgChannelInfo[channel].function != rcCalFunctionMax) {
        return;
    }
    
    if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) {
        ChannelInfo* info = &_rgChannelInfo[channel];
        
        // Switch has moved far enough to consider it as being selected for the function
        
        // Map the channel to the function
        _rgChannelInfo[channel].function = function;
        _rgFunctionChannelMapping[function] = channel;
        info->function = function;
        
Don Gagne's avatar
Don Gagne committed
        qCDebug(RadioComponentControllerLog) << "Function:" << function << "mapped to:" << channel;
Don Gagne's avatar
Don Gagne committed
        
        if (moveToNextStep) {
Don Gagne's avatar
Don Gagne committed
            _advanceState();
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value)
Don Gagne's avatar
Don Gagne committed
{
    _switchDetect(function, channel, value, true /* move to next step after detection */);
}

/// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_resetInternalCalibrationValues(void)
{
    // Set all raw channels to not reversed and center point values
Don Gagne's avatar
Don Gagne committed
    for (int i=0; i<_chanMax(); i++) {
        struct ChannelInfo* info = &_rgChannelInfo[i];
        info->function = rcCalFunctionMax;
        info->reversed = false;
Don Gagne's avatar
Don Gagne committed
        info->rcMin = RadioComponentController::_rcCalPWMCenterPoint;
        info->rcMax = RadioComponentController::_rcCalPWMCenterPoint;
        info->rcTrim = RadioComponentController::_rcCalPWMCenterPoint;
    // Initialize attitude function mapping to function channel not set
    for (size_t i=0; i<rcCalFunctionMax; i++) {
Don Gagne's avatar
Don Gagne committed
        _rgFunctionChannelMapping[i] = _chanMax();
nanthony21's avatar
nanthony21 committed
    _signalAllAttitudeValueChanges();
Don Gagne's avatar
Don Gagne committed
/// @brief Sets internal calibration values from the stored parameters
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
Don Gagne's avatar
Don Gagne committed
{
    // Initialize all function mappings to not set
    
Don Gagne's avatar
Don Gagne committed
    for (int i=0; i<_chanMax(); i++) {
        struct ChannelInfo* info = &_rgChannelInfo[i];
        info->function = rcCalFunctionMax;
    }
    
    for (size_t i=0; i<rcCalFunctionMax; i++) {
Don Gagne's avatar
Don Gagne committed
        _rgFunctionChannelMapping[i] = _chanMax();
    }
    
    // Pull parameters and update
    
    QString minTpl("RC%1_MIN");
    QString maxTpl("RC%1_MAX");
    QString trimTpl("RC%1_TRIM");
    
Don Gagne's avatar
Don Gagne committed
    for (int i = 0; i < _chanMax(); ++i) {
        struct ChannelInfo* info = &_rgChannelInfo[i];

        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;
            }
        }
Don Gagne's avatar
Don Gagne committed
        
        Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1));
        if (paramFact) {
            info->rcTrim = paramFact->rawValue().toInt();
Don Gagne's avatar
Don Gagne committed
        
        paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1));
        if (paramFact) {
            info->rcMin = paramFact->rawValue().toInt();
Don Gagne's avatar
Don Gagne committed

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

        info->reversed = _channelReversedParamValue(i);
    }
    
    for (int i=0; i<rcCalFunctionMax; i++) {
        int32_t paramChannel;
Don Gagne's avatar
Don Gagne committed
        
Don Gagne's avatar
Don Gagne committed
        const char* paramName = _functionInfo()[i].parameterName;
        if (paramName) {
            Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, paramName);
            if (paramFact) {
                paramChannel = paramFact->rawValue().toInt();
                if (paramChannel > 0 && paramChannel <= _chanMax()) {
                    _rgFunctionChannelMapping[i] = paramChannel - 1;
                    _rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i;
                }
Don Gagne's avatar
Don Gagne committed
            }
Don Gagne's avatar
Don Gagne committed
        }
    }
nanthony21's avatar
nanthony21 committed
    _signalAllAttitudeValueChanges();
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::spektrumBindMode(int mode)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    _uas->pairRX(0, mode);
Don Gagne's avatar
Don Gagne committed
/// @brief Validates the current settings against the calibration rules resetting values as necessary.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_validateCalibration(void)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    for (int chan = 0; chan<_chanMax(); chan++) {
Don Gagne's avatar
Don Gagne committed
        struct ChannelInfo* info = &_rgChannelInfo[chan];
        
        if (chan < _chanCount) {
            // Validate Min/Max values. Although the channel appears as available we still may
            // not have good min/max/trim values for it. Set to defaults if needed.
            if (info->rcMin > _rcCalPWMValidMinValue || info->rcMax < _rcCalPWMValidMaxValue) {
Don Gagne's avatar
Don Gagne committed
                qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting channel" << chan;
Don Gagne's avatar
Don Gagne committed
                info->rcMin = _rcCalPWMDefaultMinValue;
                info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
                info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
            } else {
                switch (_rgChannelInfo[chan].function) {
                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
            }
        } else {
            // Unavailable channels are set to defaults
Don Gagne's avatar
Don Gagne committed
            qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting unavailable channel" << chan;
Don Gagne's avatar
Don Gagne committed
            info->rcMin = _rcCalPWMDefaultMinValue;
            info->rcMax = _rcCalPWMDefaultMaxValue;
Don Gagne's avatar
Don Gagne committed
            info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2);
Don Gagne's avatar
Don Gagne committed
            info->reversed = false;
        }
    }
}


/// @brief Saves the rc calibration values to the board parameters.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_writeCalibration(void)
    if (!_uas) return;
    if (_px4Vehicle()) {
        _uas->stopCalibration();
    }
Don Gagne's avatar
Don Gagne committed
    if (!_px4Vehicle() && (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER || _vehicle->multiRotor()) &&  _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed) {
        // 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();
        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;

            Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel));
            if (paramFact) {
                paramFact->setRawValue((float)info->rcTrim);
            }
            paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel));
            if (paramFact) {
                paramFact->setRawValue((float)info->rcMin);
            }
            paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel));
            if (paramFact) {
                paramFact->setRawValue((float)info->rcMax);
Don Gagne's avatar
Don Gagne committed

            // 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
            // 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()) {
                // APM multi-rotor has a backwards interpretation of "reversed" on the Pitch control. So be careful.
                if (_px4Vehicle() || info->function != rcCalFunctionPitch) {
                    reversed = info->reversed;
                } else {
                    reversed = !info->reversed;
                _setChannelReversedParamValue(chan, reversed);
            }
        }

        // 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);
                    }
Don Gagne's avatar
Don Gagne committed
            }
        }
Don Gagne's avatar
Don Gagne committed
    if (_px4Vehicle()) {
        // If the RC_CHAN_COUNT parameter is available write the channel count
        if (parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT")) {
            getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->setRawValue(_chanCount);
        }
Don Gagne's avatar
Don Gagne committed
    _stopCalibration();
    _setInternalCalibrationValuesFromParameters();
Don Gagne's avatar
Don Gagne committed
/// @brief Starts the calibration process
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_startCalibration(void)
    if (_chanCount < _chanMinimum) {
        qWarning() << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum";
        return;
    }
Don Gagne's avatar
Don Gagne committed
    _resetInternalCalibrationValues();
    
    // Let the mav known we are starting calibration. This should turn off motors and so forth.
    if (_px4Vehicle()) {
        _uas->startCalibration(UASInterface::StartCalibrationRadio);
    }
Don Gagne's avatar
Don Gagne committed
    _nextButton->setProperty("text", "Next");
    _cancelButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
    _currentStep = 0;
    _setupCurrentState();
Don Gagne's avatar
Don Gagne committed
/// @brief Cancels the calibration process, setting things back to initial state.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_stopCalibration(void)
Don Gagne's avatar
Don Gagne committed
    _currentStep = -1;
    if (_uas) {
        if (_px4Vehicle()) {
            _uas->stopCalibration();
        }
Don Gagne's avatar
Don Gagne committed
        _setInternalCalibrationValuesFromParameters();
    } else {
        _resetInternalCalibrationValues();
Don Gagne's avatar
Don Gagne committed
    _statusText->setProperty("text", "");
Don Gagne's avatar
Don Gagne committed
    _nextButton->setProperty("text", "Calibrate");
    _nextButton->setEnabled(true);
    _cancelButton->setEnabled(false);
    _skipButton->setEnabled(false);
    
    _setHelpImage(_imageCenter);
Don Gagne's avatar
Don Gagne committed
/// @brief Saves the current channel values, so that we can detect when the use moves an input.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_rcCalSaveCurrentValues(void)
Don Gagne's avatar
Don Gagne committed
    for (int i = 0; i < _chanMax(); i++) {
Don Gagne's avatar
Don Gagne committed
        _rcValueSave[i] = _rcRawValue[i];
        qCDebug(RadioComponentControllerLog) << "_rcCalSaveCurrentValues channel:value" << i << _rcValueSave[i];
Don Gagne's avatar
Don Gagne committed
    }
}

/// @brief Set up the Save state of calibration.
Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_rcCalSave(void)
{
    _rcCalState = rcCalStateSave;
    
Don Gagne's avatar
Don Gagne committed
    _statusText->setProperty("text",
                             "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.");
Don Gagne's avatar
Don Gagne committed
    _nextButton->setEnabled(true);
    _skipButton->setEnabled(false);
    _cancelButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
    
    // 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
void RadioComponentController::_loadSettings(void)
{
    QSettings settings;
    
    settings.beginGroup(_settingsGroup);
    _transmitterMode = settings.value(_settingsKeyTransmitterMode, 2).toInt();
    settings.endGroup();
    
    if (_transmitterMode != 1 || _transmitterMode != 2) {
        _transmitterMode = 2;
    }
}

Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_storeSettings(void)
{
    QSettings settings;
    
    settings.beginGroup(_settingsGroup);
    settings.setValue(_settingsKeyTransmitterMode, _transmitterMode);
    settings.endGroup();
}

Don Gagne's avatar
Don Gagne committed
void RadioComponentController::_setHelpImage(const char* imageFile)
{
    QString file = _imageFilePrefix;
    
    if (_transmitterMode == 1) {
        file += _imageFileMode1Dir;
    } else if (_transmitterMode == 2) {
        file += _imageFileMode2Dir;
    } else {
        qWarning() << "Internal error: Bad _transmitterMode value";
        return;
    }
    file += imageFile;
    
Don Gagne's avatar
Don Gagne committed
    qCDebug(RadioComponentControllerLog) << "_setHelpImage" << file;
Don Gagne's avatar
Don Gagne committed
    _imageHelp = file;
    emit imageHelpChanged(file);
}

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

int RadioComponentController::rollChannelRCValue(void)
{    
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rcRawValue[rcCalFunctionRoll];
    } else {
        return 1500;
    }
}

int RadioComponentController::pitchChannelRCValue(void)
{
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rcRawValue[rcCalFunctionPitch];
    } else {
        return 1500;
    }
}

int RadioComponentController::yawChannelRCValue(void)
{
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rcRawValue[rcCalFunctionYaw];
    } else {
        return 1500;
    }
}

int RadioComponentController::throttleChannelRCValue(void)
{
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rcRawValue[rcCalFunctionThrottle];
    } else {
        return 1500;
    }
}

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

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

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

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

bool RadioComponentController::rollChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionRoll]].reversed;
    } else {
        return false;
    }
}

bool RadioComponentController::pitchChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionPitch]].reversed;
    } else {
        return false;
    }
}

bool RadioComponentController::yawChannelReversed(void)
{
Don Gagne's avatar
Don Gagne committed
    if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax()) {
Don Gagne's avatar
Don Gagne committed
        return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionYaw]].reversed;