FlightModeConfig.cc 8.96 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

/// @file
///     @brief Flight Mode Configuration
///     @author Don Gagne <don@thegagnes.com

#include "FlightModeConfig.h"
#include "UASManager.h"
#include "QGCMessageBox.h"

const char* FlightModeConfig::_modeSwitchParam = "RC_MAP_MODE_SW";
const char* FlightModeConfig::_manualSwitchParam = "RC_MAP_ACRO_SW";
const char* FlightModeConfig::_assistSwitchParam = "RC_MAP_POSCTL_SW";
const char* FlightModeConfig::_returnSwitchParam = "RC_MAP_RETURN_SW";
const char* FlightModeConfig::_loiterSwitchParam = "RC_MAP_LOITER_SW";

FlightModeConfig::FlightModeConfig(QWidget *parent) :
    QWidget(parent),
    _mav(NULL),
    _paramMgr(NULL),
    _ui(new Ui::FlightModeConfig)
{
    Q_CHECK_PTR(_ui);
    
    _ui->setupUi(this);
    
    // Expectation is that we have an active uas, it is connected and the parameters are ready
    _mav = UASManager::instance()->getActiveUAS();
    Q_ASSERT(_mav);
    
    _paramMgr = _mav->getParamManager();
    Q_ASSERT(_paramMgr);
    Q_ASSERT(_paramMgr->parametersReady());
        
    _componentId = _paramMgr->getDefaultComponentId();
    
    connect(_paramMgr, SIGNAL(parameterUpdated(int, QString, QVariant)), this, SLOT(_parameterUpdated(int, QString, QVariant)));
    
    _initUi();
}

/// @brief Intialize the UI elements
void FlightModeConfig::_initUi(void) {
    struct Combo2Param {
        QGCComboBox*    combo;
        QButtonGroup*   buttonGroup;
        const char*     param;
        const char*     description;
    };
    
    struct Combo2Param rgCombo2ParamMap[] = {
        { _ui->modeSwitchChannel,   _ui->modeSwitchGroup,   _modeSwitchParam,   "Mode Switch" },
        { _ui->manualSwitchChannel, _ui->manualSwitchGroup, _manualSwitchParam, "Manual Switch" },
        { _ui->assistSwitchChannel, _ui->assistSwitchGroup, _assistSwitchParam, "Assist Switch" },
        { _ui->returnSwitchChannel, _ui->returnSwitchGroup, _returnSwitchParam, "Return Switch" },
        { _ui->loiterSwitchChannel, _ui->loiterSwitchGroup, _loiterSwitchParam, "Loiter Switch" },
        { NULL,                     NULL,                   "RC_MAP_THROTTLE",  "Throttle" },
        { NULL,                     NULL,                   "RC_MAP_YAW",       "Rudder" },
        { NULL,                     NULL,                   "RC_MAP_ROLL",      "Aileron" },
        { NULL,                     NULL,                   "RC_MAP_PITCH",     "Elevator" },
        { NULL,                     NULL,                   "RC_MAP_AUX1",      "Aux1" },
        { NULL,                     NULL,                   "RC_MAP_AUX2",      "Aux2" },
        { NULL,                     NULL,                   "RC_MAP_AUX3",      "Aux3" }
    };
    
    // Setup up maps
    for (size_t i=0; i<sizeof(rgCombo2ParamMap)/sizeof(rgCombo2ParamMap[0]); i++) {
        struct Combo2Param* map = &rgCombo2ParamMap[i];
        
        if (map->combo) {
            Q_ASSERT(!_mapChannelCombo2Param.contains(map->combo));
            _mapChannelCombo2Param[map->combo] = map->param;

            Q_ASSERT(!_mapChannelCombo2ButtonGroup.contains(map->combo));
            _mapChannelCombo2ButtonGroup[map->combo] = map->buttonGroup;
            
            // We connect to activated because we only want signals from user initiated changes
            connect(map->combo, SIGNAL(activated(int)), this, SLOT(_channelSelected(int)));
        }
        
        Q_ASSERT(!_mapParam2FunctionInfo.contains(map->param));
        _mapParam2FunctionInfo[map->param] = map->description;
    }
    
    _updateAllSwitches();
}

void FlightModeConfig::_updateAllSwitches(void)
{
    foreach(QGCComboBox* combo, _mapChannelCombo2Param.keys()) {
        _updateSwitchUiGroup(combo);
    }
}

/// @brief Selects the channel in the combo for the given parameter
void FlightModeConfig::_selectChannelForParam(QGCComboBox* combo, const QString& parameter)
{
    int channel = _getChannelMapForParam(parameter);
    
    int index = combo->findData(channel);
    Q_ASSERT(index != -1);
    
    combo->setCurrentIndex(index);
}

/// @brief Fills a channel selection combo box with channel values
void FlightModeConfig::_updateSwitchUiGroup(QGCComboBox* combo)
{
    QMap<int, QString> mapChannelUsed2Description;
    
    // Make a map of all channels currently mapped
    foreach(QString paramId, _mapParam2FunctionInfo.keys()) {
        int channel = _getChannelMapForParam(paramId);
        if (channel != 0) {
            mapChannelUsed2Description[channel] = _mapParam2FunctionInfo[paramId];
        }
    }
    
    combo->clear();
    combo->addItem("Disabled", 0);
    for (int i=1; i<=_maxChannels; i++) {
        QString comboText = QString("Channel %1").arg(i);
        
        if (mapChannelUsed2Description.contains(i)) {
            comboText += QString(" (%1)").arg(mapChannelUsed2Description[i]);
        }
        
        combo->addItem(comboText, i);
    }
    
    _selectChannelForParam(combo, _mapChannelCombo2Param[combo]);
    
    // Enable/Disable radio buttons appropriately
    
    int channelMap = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
    
    Q_ASSERT(_mapChannelCombo2ButtonGroup.contains(combo));
    Q_ASSERT(_mapChannelCombo2ButtonGroup[combo]->buttons().count() > 0);
    
    foreach(QAbstractButton* button, _mapChannelCombo2ButtonGroup[combo]->buttons()) {
        QRadioButton* radio = qobject_cast<QRadioButton*>(button);
        
        Q_ASSERT(radio);
        
        radio->setEnabled(channelMap != 0);
    }
}

/// @brief Returns channel mapping for the specified parameters
int FlightModeConfig::_getChannelMapForParam(const QString& paramId)
{
    QVariant value;
    bool found = _paramMgr->getParameterValue(_componentId, paramId, value);
    Q_UNUSED(found);
    Q_ASSERT(found);
    
    bool conversionOk;
    int channel = value.toInt(&conversionOk);
    Q_UNUSED(conversionOk);
    Q_ASSERT(conversionOk);
    
    return channel;
}

/// @brief Called when a selection occurs in one of the channel combo boxes
void FlightModeConfig::_channelSelected(int requestedMapping)
{
    QGCComboBox* combo = qobject_cast<QGCComboBox*>(sender());
    Q_ASSERT(combo);
    Q_ASSERT(_mapChannelCombo2Param.contains(combo));
    
    // Check for no-op
    
    int currentMapping = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
    if (currentMapping == requestedMapping) {
        return;
    }
    
    // Make sure that channel is not already mapped
    
    if (requestedMapping == 0) {
        // Channel was disabled
        if (combo == _ui->modeSwitchChannel) {
            // Mode switch is not allowed to be disabled.
            QGCMessageBox::warning(tr("Flight Mode"), "Mode Switch is a required switch and cannot be disabled.");
            _selectChannelForParam(combo, _mapChannelCombo2Param[combo]);
            return;
        }
    } else {
        // Channel was remapped to a non-disabled channel
        foreach(QString paramId, _mapParam2FunctionInfo.keys()) {
            int usedChannelMap = _getChannelMapForParam(paramId);

            if (requestedMapping == usedChannelMap) {
                QGCMessageBox::warning(tr("Flight Mode"), "You cannot use a channel which is already mapped.");
                _selectChannelForParam(combo, _mapChannelCombo2Param[combo]);
                return;
            }
        }
    }
    
    // Save the new setting to the parameter
    _paramMgr->setParameter(_componentId, _mapChannelCombo2Param[combo], requestedMapping);
    _paramMgr->sendPendingParameters(true, false);
}

void FlightModeConfig::_parameterUpdated(int componentId, QString parameter, QVariant value)
{
    Q_UNUSED(componentId);
    Q_UNUSED(value);
    
    // If this is a function mapping parameter update the combos
    if (_mapParam2FunctionInfo.contains(parameter)) {
        _updateAllSwitches();
    }
    
    // Finally if RC Calibration suddenly needs to be re-done disable the entire widget and inform user
    if (parameter == _modeSwitchParam) {
        // FIXME: Do something more than disable
        if (isEnabled() == false && value.toInt() != 0) {
            setEnabled(true);
        } else if (isEnabled() == true && value.toInt() == 0) {
            setEnabled(false);
        }
    }
}