SensorsComponentController.cc 15.2 KB
Newer Older
Don Gagne's avatar
Don Gagne committed
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
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009, 2015 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
///     @author Don Gagne <don@thegagnes.com>

#include "SensorsComponentController.h"
#include "QGCMAVLink.h"
#include "UASManager.h"
30
#include "QGCMessageBox.h"
Don Gagne's avatar
Don Gagne committed
31 32 33 34

#include <QVariant>
#include <QQmlProperty>

Don Gagne's avatar
Don Gagne committed
35
SensorsComponentController::SensorsComponentController(void) :
36 37
    _statusLog(NULL),
    _progressBar(NULL),
Don Gagne's avatar
Don Gagne committed
38 39 40 41
    _compassButton(NULL),
    _gyroButton(NULL),
    _accelButton(NULL),
    _airspeedButton(NULL),
42
    _levelButton(NULL),
Don Gagne's avatar
Don Gagne committed
43
    _cancelButton(NULL),
Don Gagne's avatar
Don Gagne committed
44
    _showOrientationCalArea(false),
45
    _gyroCalInProgress(false),
Don Gagne's avatar
Don Gagne committed
46 47 48 49 50 51 52 53
    _magCalInProgress(false),
    _accelCalInProgress(false),
    _orientationCalDownSideDone(false),
    _orientationCalUpsideDownSideDone(false),
    _orientationCalLeftSideDone(false),
    _orientationCalRightSideDone(false),
    _orientationCalNoseDownSideDone(false),
    _orientationCalTailDownSideDone(false),
Don Gagne's avatar
Don Gagne committed
54 55 56 57 58 59
    _orientationCalDownSideVisible(false),
    _orientationCalUpsideDownSideVisible(false),
    _orientationCalLeftSideVisible(false),
    _orientationCalRightSideVisible(false),
    _orientationCalNoseDownSideVisible(false),
    _orientationCalTailDownSideVisible(false),
Don Gagne's avatar
Don Gagne committed
60 61 62 63 64 65
    _orientationCalDownSideInProgress(false),
    _orientationCalUpsideDownSideInProgress(false),
    _orientationCalLeftSideInProgress(false),
    _orientationCalRightSideInProgress(false),
    _orientationCalNoseDownSideInProgress(false),
    _orientationCalTailDownSideInProgress(false),
Don Gagne's avatar
Don Gagne committed
66 67 68 69
    _orientationCalDownSideRotate(false),
    _orientationCalLeftSideRotate(false),
    _orientationCalNoseDownSideRotate(false),
    _unknownFirmwareVersion(false),
Don Gagne's avatar
Don Gagne committed
70
    _waitingForCancel(false)
Don Gagne's avatar
Don Gagne committed
71
{
Don Gagne's avatar
Don Gagne committed
72

Don Gagne's avatar
Don Gagne committed
73 74 75 76 77 78 79 80 81 82 83 84 85 86 87
}

/// Appends the specified text to the status log area in the ui
void SensorsComponentController::_appendStatusLog(const QString& text)
{
    Q_ASSERT(_statusLog);
    
    QVariant returnedValue;
    QVariant varText = text;
    QMetaObject::invokeMethod(_statusLog,
                              "append",
                              Q_RETURN_ARG(QVariant, returnedValue),
                              Q_ARG(QVariant, varText));
}

Don Gagne's avatar
Don Gagne committed
88
void SensorsComponentController::_startLogCalibration(void)
Don Gagne's avatar
Don Gagne committed
89
{
Don Gagne's avatar
Don Gagne committed
90
    _unknownFirmwareVersion = false;
91 92
    _hideAllCalAreas();
    
Don Gagne's avatar
Don Gagne committed
93 94 95 96 97 98 99
    connect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
    
    _cancelButton->setEnabled(false);
}

void SensorsComponentController::_startVisualCalibration(void)
{
100 101 102 103
    _compassButton->setEnabled(false);
    _gyroButton->setEnabled(false);
    _accelButton->setEnabled(false);
    _airspeedButton->setEnabled(false);
104
    _levelButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
105 106 107
    _cancelButton->setEnabled(true);
    
    _progressBar->setProperty("value", 0);
108 109
}

Don Gagne's avatar
Don Gagne committed
110
void SensorsComponentController::_stopCalibration(SensorsComponentController::StopCalibrationCode code)
111
{
Don Gagne's avatar
Don Gagne committed
112
    disconnect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
Don Gagne's avatar
Don Gagne committed
113
    
114 115 116 117
    _compassButton->setEnabled(true);
    _gyroButton->setEnabled(true);
    _accelButton->setEnabled(true);
    _airspeedButton->setEnabled(true);
118
    _levelButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140
    _cancelButton->setEnabled(false);
    
    if (code == StopCalibrationSuccess) {
        _orientationCalDownSideDone = true;
        _orientationCalUpsideDownSideDone = true;
        _orientationCalLeftSideDone = true;
        _orientationCalRightSideDone = true;
        _orientationCalTailDownSideDone = true;
        _orientationCalNoseDownSideDone = true;
        _orientationCalDownSideInProgress = false;
        _orientationCalUpsideDownSideInProgress = false;
        _orientationCalLeftSideInProgress = false;
        _orientationCalRightSideInProgress = false;
        _orientationCalNoseDownSideInProgress = false;
        _orientationCalTailDownSideInProgress = false;
        emit orientationCalSidesDoneChanged();
        emit orientationCalSidesInProgressChanged();
        
        _progressBar->setProperty("value", 1);
    } else {
        _progressBar->setProperty("value", 0);
    }
141
    
Don Gagne's avatar
Don Gagne committed
142 143 144
    _waitingForCancel = false;
    emit waitingForCancelChanged();

145 146
    _refreshParams();
    
Don Gagne's avatar
Don Gagne committed
147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165
    switch (code) {
        case StopCalibrationSuccess:
            _orientationCalAreaHelpText->setProperty("text", "Calibration complete");
            emit resetStatusTextArea();
            if (_magCalInProgress) {
                emit setCompassRotations();
            }
            break;
            
        case StopCalibrationCancelled:
            emit resetStatusTextArea();
            _hideAllCalAreas();
            break;
            
        default:
            // Assume failed
            _hideAllCalAreas();
            QGCMessageBox::warning("Calibration", "Calibration failed. Calibration log will be displayed.");
            break;
166
    }
Don Gagne's avatar
Don Gagne committed
167 168 169 170
    
    _magCalInProgress = false;
    _accelCalInProgress = false;
    _gyroCalInProgress = false;
171 172 173 174
}

void SensorsComponentController::calibrateGyro(void)
{
Don Gagne's avatar
Don Gagne committed
175 176
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationGyro);
Don Gagne's avatar
Don Gagne committed
177 178 179 180
}

void SensorsComponentController::calibrateCompass(void)
{
Don Gagne's avatar
Don Gagne committed
181 182
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationMag);
Don Gagne's avatar
Don Gagne committed
183 184 185 186
}

void SensorsComponentController::calibrateAccel(void)
{
Don Gagne's avatar
Don Gagne committed
187 188
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAccel);
Don Gagne's avatar
Don Gagne committed
189 190
}

191 192 193 194 195 196
void SensorsComponentController::calibrateLevel(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationLevel);
}

Don Gagne's avatar
Don Gagne committed
197 198
void SensorsComponentController::calibrateAirspeed(void)
{
Don Gagne's avatar
Don Gagne committed
199 200
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAirspeed);
Don Gagne's avatar
Don Gagne committed
201 202 203 204 205 206 207 208 209 210 211 212 213
}

void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
{
    Q_UNUSED(compId);
    Q_UNUSED(severity);
    
    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    if (uasId != uas->getUASID()) {
        return;
    }
    
214 215 216 217 218 219 220 221 222 223 224
    if (text.contains("progress <")) {
        QString percent = text.split("<").last().split(">").first();
        bool ok;
        int p = percent.toInt(&ok);
        if (ok) {
            Q_ASSERT(_progressBar);
            _progressBar->setProperty("value", (float)(p / 100.0));
        }
        return;
    }

Don Gagne's avatar
Don Gagne committed
225
    _appendStatusLog(text);
Don Gagne's avatar
Don Gagne committed
226 227 228 229 230 231 232 233 234 235 236 237
    
    if (_unknownFirmwareVersion) {
        // We don't know how to do visual cal with the version of firwmare
        return;
    }
    
    // All calibration messages start with [cal]
    QString calPrefix("[cal] ");
    if (!text.startsWith(calPrefix)) {
        return;
    }
    text = text.right(text.length() - calPrefix.length());
238

Don Gagne's avatar
Don Gagne committed
239 240 241 242 243 244 245 246 247 248
    QString calStartPrefix("calibration started: ");
    if (text.startsWith(calStartPrefix)) {
        text = text.right(text.length() - calStartPrefix.length());
        
        // Split version number and cal type
        QStringList parts = text.split(" ");
        if (parts.count() != 2 && parts[0].toInt() != 1) {
            _unknownFirmwareVersion = true;
            qDebug() << "Unknown cal firmware version, using log";
            return;
Don Gagne's avatar
Don Gagne committed
249
        }
Don Gagne's avatar
Don Gagne committed
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
        
        _startVisualCalibration();
        
        text = parts[1];
        if (text == "accel" || text == "mag" || text == "gyro") {
            // Reset all progress indication
            _orientationCalDownSideDone = false;
            _orientationCalUpsideDownSideDone = false;
            _orientationCalLeftSideDone = false;
            _orientationCalRightSideDone = false;
            _orientationCalTailDownSideDone = false;
            _orientationCalNoseDownSideDone = false;
            _orientationCalDownSideInProgress = false;
            _orientationCalUpsideDownSideInProgress = false;
            _orientationCalLeftSideInProgress = false;
            _orientationCalRightSideInProgress = false;
            _orientationCalNoseDownSideInProgress = false;
            _orientationCalTailDownSideInProgress = false;
            
            // Reset all visibility
            _orientationCalDownSideVisible = false;
            _orientationCalUpsideDownSideVisible = false;
            _orientationCalLeftSideVisible = false;
            _orientationCalRightSideVisible = false;
            _orientationCalTailDownSideVisible = false;
            _orientationCalNoseDownSideVisible = false;
            
            _orientationCalAreaHelpText->setProperty("text", "Place your vehicle into one of the Incomplete orientations shown below and hold it still");
            
            if (text == "accel") {
                _accelCalInProgress = true;
                _orientationCalDownSideVisible = true;
                _orientationCalUpsideDownSideVisible = true;
                _orientationCalLeftSideVisible = true;
                _orientationCalRightSideVisible = true;
                _orientationCalTailDownSideVisible = true;
                _orientationCalNoseDownSideVisible = true;
            } else if (text == "mag") {
                _magCalInProgress = true;
                _orientationCalDownSideVisible = true;
                _orientationCalLeftSideVisible = true;
                _orientationCalNoseDownSideVisible = true;
            } else if (text == "gyro") {
                _gyroCalInProgress = true;
                _orientationCalDownSideVisible = true;
            } else {
                Q_ASSERT(false);
            }
            emit orientationCalSidesDoneChanged();
            emit orientationCalSidesVisibleChanged();
            emit orientationCalSidesInProgressChanged();
            _updateAndEmitShowOrientationCalArea(true);
Don Gagne's avatar
Don Gagne committed
302
        }
Don Gagne's avatar
Don Gagne committed
303 304 305 306
        return;
    }
    
    if (text.endsWith("orientation detected")) {
Don Gagne's avatar
Don Gagne committed
307 308
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side started" << side;
Don Gagne's avatar
Don Gagne committed
309
        
Don Gagne's avatar
Don Gagne committed
310 311
        if (side == "down") {
            _orientationCalDownSideInProgress = true;
Don Gagne's avatar
Don Gagne committed
312 313 314
            if (_magCalInProgress) {
                _orientationCalDownSideRotate = true;
            }
315
        } else if (side == "up") {
Don Gagne's avatar
Don Gagne committed
316
            _orientationCalUpsideDownSideInProgress = true;
317
        } else if (side == "left") {
Don Gagne's avatar
Don Gagne committed
318
            _orientationCalLeftSideInProgress = true;
Don Gagne's avatar
Don Gagne committed
319 320 321
            if (_magCalInProgress) {
                _orientationCalLeftSideRotate = true;
            }
322
        } else if (side == "right") {
Don Gagne's avatar
Don Gagne committed
323
            _orientationCalRightSideInProgress = true;
324
        } else if (side == "front") {
Don Gagne's avatar
Don Gagne committed
325
            _orientationCalNoseDownSideInProgress = true;
Don Gagne's avatar
Don Gagne committed
326 327 328
            if (_magCalInProgress) {
                _orientationCalNoseDownSideRotate = true;
            }
329
        } else if (side == "back") {
Don Gagne's avatar
Don Gagne committed
330
            _orientationCalTailDownSideInProgress = true;
331
        }
Don Gagne's avatar
Don Gagne committed
332 333 334 335 336 337 338
        
        if (_magCalInProgress) {
            _orientationCalAreaHelpText->setProperty("text", "Rotate the vehicle continuously as shown in the diagram until marked as Completed");
        } else {
            _orientationCalAreaHelpText->setProperty("text", "Hold still in the current orientation");
        }
        
Don Gagne's avatar
Don Gagne committed
339
        emit orientationCalSidesInProgressChanged();
Don Gagne's avatar
Don Gagne committed
340 341 342 343 344
        emit orientationCalSidesRotateChanged();
        return;
    }
    
    if (text.endsWith("side done, rotate to a different side")) {
345 346
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side finished" << side;
Don Gagne's avatar
Don Gagne committed
347
        
348
        if (side == "down") {
Don Gagne's avatar
Don Gagne committed
349 350
            _orientationCalDownSideInProgress = false;
            _orientationCalDownSideDone = true;
Don Gagne's avatar
Don Gagne committed
351
            _orientationCalDownSideRotate = false;
352
        } else if (side == "up") {
Don Gagne's avatar
Don Gagne committed
353 354
            _orientationCalUpsideDownSideInProgress = false;
            _orientationCalUpsideDownSideDone = true;
355
        } else if (side == "left") {
Don Gagne's avatar
Don Gagne committed
356 357
            _orientationCalLeftSideInProgress = false;
            _orientationCalLeftSideDone = true;
Don Gagne's avatar
Don Gagne committed
358
            _orientationCalLeftSideRotate = false;
359
        } else if (side == "right") {
Don Gagne's avatar
Don Gagne committed
360 361
            _orientationCalRightSideInProgress = false;
            _orientationCalRightSideDone = true;
362
        } else if (side == "front") {
Don Gagne's avatar
Don Gagne committed
363 364
            _orientationCalNoseDownSideInProgress = false;
            _orientationCalNoseDownSideDone = true;
Don Gagne's avatar
Don Gagne committed
365
            _orientationCalNoseDownSideRotate = false;
366
        } else if (side == "back") {
Don Gagne's avatar
Don Gagne committed
367 368
            _orientationCalTailDownSideInProgress = false;
            _orientationCalTailDownSideDone = true;
369
        }
Don Gagne's avatar
Don Gagne committed
370 371 372
        
        _orientationCalAreaHelpText->setProperty("text", "Place you vehicle into one of the orientations shown below and hold it still");

Don Gagne's avatar
Don Gagne committed
373 374
        emit orientationCalSidesInProgressChanged();
        emit orientationCalSidesDoneChanged();
Don Gagne's avatar
Don Gagne committed
375 376
        emit orientationCalSidesRotateChanged();
        return;
377
    }
Don Gagne's avatar
Don Gagne committed
378
    
Don Gagne's avatar
Don Gagne committed
379 380 381 382
    QString calCompletePrefix("calibration done:");
    if (text.startsWith(calCompletePrefix)) {
        _stopCalibration(StopCalibrationSuccess);
        return;
383
    }
Don Gagne's avatar
Don Gagne committed
384 385 386 387
    
    if (text.startsWith("calibration cancelled")) {
        _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
        return;
388 389
    }
    
Don Gagne's avatar
Don Gagne committed
390 391 392 393 394 395 396 397
    if (text.startsWith("calibration failed")) {
        _stopCalibration(StopCalibrationFailed);
        return;
    }
}

void SensorsComponentController::_refreshParams(void)
{
Don Gagne's avatar
Don Gagne committed
398 399 400 401 402 403 404 405 406
    QStringList fastRefreshList;
    
    // We ask for a refresh on these first so that the rotation combo show up as fast as possible
    fastRefreshList << "CAL_MAG0_ID" << "CAL_MAG1_ID" << "CAL_MAG2_ID" << "CAL_MAG0_ROT" << "CAL_MAG1_ROT" << "CAL_MAG2_ROT";
    foreach (QString paramName, fastRefreshList) {
        _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName);
    }
    
    // Now ask for all to refresh
407 408
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_");
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_");
Don Gagne's avatar
Don Gagne committed
409 410 411 412 413 414
}

bool SensorsComponentController::fixedWing(void)
{
    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
415 416 417
    return uas->getSystemType() == MAV_TYPE_FIXED_WING ||
            uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
            uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR;
Don Gagne's avatar
Don Gagne committed
418
}
419

Don Gagne's avatar
Don Gagne committed
420
void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
421
{
Don Gagne's avatar
Don Gagne committed
422 423
    _showOrientationCalArea = show;
    emit showOrientationCalAreaChanged();
424 425 426 427
}

void SensorsComponentController::_hideAllCalAreas(void)
{
Don Gagne's avatar
Don Gagne committed
428 429 430
    _updateAndEmitShowOrientationCalArea(false);
}

Don Gagne's avatar
Don Gagne committed
431
void SensorsComponentController::cancelCalibration(void)
Don Gagne's avatar
Don Gagne committed
432
{
Don Gagne's avatar
Don Gagne committed
433 434 435 436 437 438
    // The firmware doesn't allow us to cancel calibration. The best we can do is wait
    // for it to timeout.
    _waitingForCancel = true;
    emit waitingForCancelChanged();
    _cancelButton->setEnabled(false);
    _uas->stopCalibration();
439
}