FlightModeConfigTest.cc 10.1 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
/*=====================================================================
 
 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/>.
 
 ======================================================================*/

#include "FlightModeConfigTest.h"
#include "UASManager.h"
#include "MockQGCUASParamManager.h"
#include "QGCMessageBox.h"

/// @file
///     @brief FlightModeConfig Widget unit test
///
///     @author Don Gagne <don@thegagnes.com>

UT_REGISTER_TEST(FlightModeConfigTest)

FlightModeConfigTest::FlightModeConfigTest(void) :
    _mockUASManager(NULL),
    _paramMgr(NULL),
    _configWidget(NULL),
    _defaultComponentId(0)
{

}

void FlightModeConfigTest::initTestCase(void)
{

}

void FlightModeConfigTest::init(void)
{
    UnitTest::init();
    
    _mockUASManager = new MockUASManager();
    Q_ASSERT(_mockUASManager);
    
    UASManager::setMockUASManager(_mockUASManager);
    
    _mockUAS = new MockUAS();
    Q_CHECK_PTR(_mockUAS);
    _paramMgr = _mockUAS->getParamManager();
    _defaultComponentId = _paramMgr->getDefaultComponentId();
    
    _mockUASManager->setMockActiveUAS(_mockUAS);
    
    struct SetupParamInfo {
        const char* param;
        int         mappedChannel;
    };
    
    struct SetupParamInfo rgSetupParamInfo[] = {
        { "RC_MAP_MODE_SW",   5 },
        { "RC_MAP_ACRO_SW",   0 },
        { "RC_MAP_POSCTL_SW", 0 },
        { "RC_MAP_RETURN_SW", 0 },
        { "RC_MAP_LOITER_SW", 0 },
        { "RC_MAP_THROTTLE",  1 },
        { "RC_MAP_YAW",       2 },
        { "RC_MAP_ROLL",      3 },
        { "RC_MAP_PITCH",     4 },
        { "RC_MAP_AUX1",      0 },
        { "RC_MAP_AUX2",      0 },
        { "RC_MAP_AUX3",      0 }
    };
    size_t crgSetupParamInfo = sizeof(rgSetupParamInfo) / sizeof(rgSetupParamInfo[0]);

    // Set initial parameter values
    for (size_t i=0; i<crgSetupParamInfo; i++) {
        struct SetupParamInfo* info = &rgSetupParamInfo[i];
        
        _paramMgr->setParameter(_defaultComponentId, info->param, info->mappedChannel);
    }

    _configWidget = new FlightModeConfig;
    Q_CHECK_PTR(_configWidget);
    _configWidget->setVisible(true);
    
    // Setup combo maps
    
    struct SetupComboInfo {
        QGCComboBox*    combo;
        QButtonGroup*   buttonGroup;
        const char*     param;
    };
    
    struct SetupComboInfo rgSetupComboInfo[] = {
        { _configWidget->_ui->modeSwitchChannel,    _configWidget->_ui->modeSwitchGroup,    "RC_MAP_MODE_SW" },
        { _configWidget->_ui->manualSwitchChannel,  _configWidget->_ui->manualSwitchGroup,  "RC_MAP_ACRO_SW" },
        { _configWidget->_ui->assistSwitchChannel,  _configWidget->_ui->assistSwitchGroup,  "RC_MAP_POSCTL_SW" },
        { _configWidget->_ui->returnSwitchChannel,  _configWidget->_ui->returnSwitchGroup,  "RC_MAP_RETURN_SW" },
        { _configWidget->_ui->loiterSwitchChannel,  _configWidget->_ui->loiterSwitchGroup,  "RC_MAP_LOITER_SW" }
    };
    size_t crgSetupComboInfo = sizeof(rgSetupComboInfo) / sizeof(rgSetupComboInfo[0]);

    Q_ASSERT(_mapChannelCombo2Param.count() == 0);
    for (size_t i=0; i<crgSetupComboInfo; i++) {
        struct SetupComboInfo* info = &rgSetupComboInfo[i];
        
        Q_ASSERT(!_mapChannelCombo2Param.contains(info->combo));
        _mapChannelCombo2Param[info->combo] = info->param;
        
        Q_ASSERT(!_mapChannelCombo2ButtonGroup.contains(info->combo));
        _mapChannelCombo2ButtonGroup[info->combo] = info->buttonGroup;
    }
}

void FlightModeConfigTest::cleanup(void)
{
    UnitTest::cleanup();
    
    Q_ASSERT(_configWidget);
    delete _configWidget;
    
    Q_ASSERT(_mockUAS);
    delete _mockUAS;
    
    UASManager::setMockUASManager(NULL);
    
    Q_ASSERT(_mockUASManager);
    delete _mockUASManager;
    
    _mapChannelCombo2Param.clear();
143
    _mapChannelCombo2ButtonGroup.clear();
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 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304
}

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

void FlightModeConfigTest::_create_test(void)
{
    // This just test widget creation which is handled in init
}

void FlightModeConfigTest::_validateInitialState_test(void)
{
    // Make sure that the combo boxes are set to the correct selections
    foreach(QGCComboBox* combo, _mapChannelCombo2Param.keys()) {
        QVariant value;
        
        Q_ASSERT(_mapChannelCombo2Param.contains(combo));
        int expectedMappedChannel = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
        
        int currentIndex = combo->currentIndex();
        QVERIFY(currentIndex != -1);
        
        int comboMappedChannel = combo->itemData(currentIndex).toInt();
        
        QCOMPARE(comboMappedChannel, expectedMappedChannel);
    }
    
    QGCComboBox* combo = _configWidget->_ui->modeSwitchChannel;

    // combo should have entry for each channel plus disabled
    QCOMPARE(combo->count(), _availableChannels + 1);
             
    for (int i=0; i<combo->count(); i++) {
        // Combo data equates to channel mapping value. These are one-base channel values with
        // 0 meaning disabled. The channel should match the index.
        QCOMPARE(i, combo->itemData(i).toInt());
        
        // Channels which are mapped are displayed after the channel number in the form "(name)".
        // Check for the ending parentheses to indicate mapped channels
        QString text = combo->itemText(i);
        if (text.endsWith(")")) {
            // Channels 1-5 are mapped
            QVERIFY(i >= 1 && i <= 5);
        } else {
            QVERIFY(!(i >= 1 && i <= 5));
        }
    }
}

void FlightModeConfigTest::_validateRCCalCheck_test(void)
{
    // Mode switch mapped is used to signal RC Calibration not complete. You must complete RC Cal before
    // doing Flight Mode Config.
    
    // Set mode switch mapping to not set
    Q_ASSERT(_mapChannelCombo2Param.contains(_configWidget->_ui->modeSwitchChannel));
    _paramMgr->setParameter(_defaultComponentId, _mapChannelCombo2Param[_configWidget->_ui->modeSwitchChannel], 0);
    
    // Widget should disable
    QCOMPARE(_configWidget->isEnabled(), false);
    
    // Set mode switch mapping to mapped
    Q_ASSERT(_mapChannelCombo2Param.contains(_configWidget->_ui->modeSwitchChannel));
    _paramMgr->setParameter(_defaultComponentId, _mapChannelCombo2Param[_configWidget->_ui->modeSwitchChannel], 5);
    
    // Widget should re-enable
    QCOMPARE(_configWidget->isEnabled(), true);
}

void FlightModeConfigTest::_attempChannelReuse_test(void)
{
    // Attempt to select a channel that is already in use for a switch mapping
    foreach(QGCComboBox* combo, _mapChannelCombo2Param.keys()) {
        
        Q_ASSERT(_mapChannelCombo2Param.contains(combo));
        int beforeMapping = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
        
        setExpectedMessageBox(QMessageBox::Ok);
        
        // Channel 1 mapped to throttle. This should pop a message box and the parameter value should
        // not change.
        combo->simulateUserSetCurrentIndex(1);
        
        checkExpectedMessageBox();
        
        int afterMapping = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
        
        QCOMPARE(beforeMapping, afterMapping);
    }
}

void FlightModeConfigTest::_validateRadioButtonEnableDisable_test(void)
{
    // Radio button should enable/disable according to selection
    foreach(QGCComboBox* combo, _mapChannelCombo2Param.keys()) {
        // Mode switch can't be disabled
        if (combo == _configWidget->_ui->modeSwitchChannel) {
            continue;
        }
        
        // Index 0 is disabled
        combo->simulateUserSetCurrentIndex(0);
        
        Q_ASSERT(_mapChannelCombo2ButtonGroup.contains(combo));
        QButtonGroup* buttonGroup = _mapChannelCombo2ButtonGroup[combo];
        
        foreach(QAbstractButton* button, buttonGroup->buttons()) {
            QRadioButton* radio = qobject_cast<QRadioButton*>(button);
            Q_ASSERT(radio);
            
            QCOMPARE(radio->isEnabled(), false);
        }
        
        // Index 6 should be a valid mapping
        combo->simulateUserSetCurrentIndex(6);
        
        foreach(QAbstractButton* button, buttonGroup->buttons()) {
            QRadioButton* radio = qobject_cast<QRadioButton*>(button);
            Q_ASSERT(radio);
            
            QCOMPARE(radio->isEnabled(), true);
        }

        // Set back to disabled for next iteration through loop. Otherwise we'll error out
        // with the channel already in use
        combo->simulateUserSetCurrentIndex(0);
    }
}

void FlightModeConfigTest::_validateModeSwitchMustBeEnabled_test(void)
{
    QGCComboBox* modeCombo = _configWidget->_ui->modeSwitchChannel;
    
    Q_ASSERT(_mapChannelCombo2Param.contains(modeCombo));
    int beforeMapping = _getChannelMapForParam(_mapChannelCombo2Param[modeCombo]);
    
    setExpectedMessageBox(QMessageBox::Ok);
    
    // Index 0 is disabled. This should pop a message box and the parameter value should
    // not change.
    modeCombo->simulateUserSetCurrentIndex(0);
    
    checkExpectedMessageBox();
    
    int afterMapping = _getChannelMapForParam(_mapChannelCombo2Param[modeCombo]);
    
    QCOMPARE(beforeMapping, afterMapping);
}