APMSensorsComponentController.cc 17 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/
9

Don Gagne's avatar
Don Gagne committed
10 11 12 13 14

#include "APMSensorsComponentController.h"
#include "QGCMAVLink.h"
#include "UAS.h"
#include "QGCApplication.h"
15
#include "APMAutoPilotPlugin.h"
Don Gagne's avatar
Don Gagne committed
16 17 18 19 20 21 22 23 24 25 26 27 28

#include <QVariant>
#include <QQmlProperty>

QGC_LOGGING_CATEGORY(APMSensorsComponentControllerLog, "APMSensorsComponentControllerLog")

APMSensorsComponentController::APMSensorsComponentController(void) :
    _statusLog(NULL),
    _progressBar(NULL),
    _compassButton(NULL),
    _accelButton(NULL),
    _nextButton(NULL),
    _cancelButton(NULL),
Don Gagne's avatar
Don Gagne committed
29
    _setOrientationsButton(NULL),
Don Gagne's avatar
Don Gagne committed
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
    _showOrientationCalArea(false),
    _magCalInProgress(false),
    _accelCalInProgress(false),
    _orientationCalDownSideDone(false),
    _orientationCalUpsideDownSideDone(false),
    _orientationCalLeftSideDone(false),
    _orientationCalRightSideDone(false),
    _orientationCalNoseDownSideDone(false),
    _orientationCalTailDownSideDone(false),
    _orientationCalDownSideVisible(false),
    _orientationCalUpsideDownSideVisible(false),
    _orientationCalLeftSideVisible(false),
    _orientationCalRightSideVisible(false),
    _orientationCalNoseDownSideVisible(false),
    _orientationCalTailDownSideVisible(false),
    _orientationCalDownSideInProgress(false),
    _orientationCalUpsideDownSideInProgress(false),
    _orientationCalLeftSideInProgress(false),
    _orientationCalRightSideInProgress(false),
    _orientationCalNoseDownSideInProgress(false),
    _orientationCalTailDownSideInProgress(false),
    _orientationCalDownSideRotate(false),
    _orientationCalUpsideDownSideRotate(false),
    _orientationCalLeftSideRotate(false),
    _orientationCalRightSideRotate(false),
    _orientationCalNoseDownSideRotate(false),
    _orientationCalTailDownSideRotate(false),
    _waitingForCancel(false)
{
59 60 61
    _compassCal.setVehicle(_vehicle);
    connect(&_compassCal, &APMCompassCal::vehicleTextMessage, this, &APMSensorsComponentController::_handleUASTextMessage);

62
    APMAutoPilotPlugin * apmPlugin = qobject_cast<APMAutoPilotPlugin*>(_vehicle->autopilotPlugin());
Don Gagne's avatar
Don Gagne committed
63

64
    _sensorsComponent = apmPlugin->sensorsComponent();
65
    connect(_sensorsComponent, &VehicleComponent::setupCompleteChanged, this, &APMSensorsComponentController::setupNeededChanged);
Don Gagne's avatar
Don Gagne committed
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88
}

/// Appends the specified text to the status log area in the ui
void APMSensorsComponentController::_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));
}

void APMSensorsComponentController::_startLogCalibration(void)
{
    _hideAllCalAreas();
    
    connect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
    
    _compassButton->setEnabled(false);
    _accelButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
89
    _setOrientationsButton->setEnabled(false);
90 91 92
    if (_accelCalInProgress) {
        _nextButton->setEnabled(true);
    }
Don Gagne's avatar
Don Gagne committed
93 94 95 96 97 98 99
    _cancelButton->setEnabled(false);
}

void APMSensorsComponentController::_startVisualCalibration(void)
{
    _compassButton->setEnabled(false);
    _accelButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
100
    _setOrientationsButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
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
    _cancelButton->setEnabled(true);

    _resetInternalState();
    
    _progressBar->setProperty("value", 0);
}

void APMSensorsComponentController::_resetInternalState(void)
{
    _orientationCalDownSideDone = true;
    _orientationCalUpsideDownSideDone = true;
    _orientationCalLeftSideDone = true;
    _orientationCalRightSideDone = true;
    _orientationCalTailDownSideDone = true;
    _orientationCalNoseDownSideDone = true;
    _orientationCalDownSideInProgress = false;
    _orientationCalUpsideDownSideInProgress = false;
    _orientationCalLeftSideInProgress = false;
    _orientationCalRightSideInProgress = false;
    _orientationCalNoseDownSideInProgress = false;
    _orientationCalTailDownSideInProgress = false;
    _orientationCalDownSideRotate = false;
    _orientationCalUpsideDownSideRotate = false;
    _orientationCalLeftSideRotate = false;
    _orientationCalRightSideRotate = false;
    _orientationCalNoseDownSideRotate = false;
    _orientationCalTailDownSideRotate = false;

    emit orientationCalSidesRotateChanged();
    emit orientationCalSidesDoneChanged();
    emit orientationCalSidesInProgressChanged();
}

void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code)
{
136 137 138 139
    if (_accelCalInProgress) {
        _vehicle->setConnectionLostEnabled(true);
    }

Don Gagne's avatar
Don Gagne committed
140 141 142 143
    disconnect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
    
    _compassButton->setEnabled(true);
    _accelButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
144
    _setOrientationsButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
145 146
    _nextButton->setEnabled(false);
    _cancelButton->setEnabled(false);
147

Don Gagne's avatar
Don Gagne committed
148 149 150 151 152 153 154 155 156 157 158 159 160
    if (code == StopCalibrationSuccess) {
        _resetInternalState();
        _progressBar->setProperty("value", 1);
    } else {
        _progressBar->setProperty("value", 0);
    }
    
    _waitingForCancel = false;
    emit waitingForCancelChanged();

    _refreshParams();
    
    switch (code) {
161 162 163
    case StopCalibrationSuccess:
        _orientationCalAreaHelpText->setProperty("text", "Calibration complete");
        emit resetStatusTextArea();
Don Gagne's avatar
Don Gagne committed
164
        emit calibrationComplete();
165 166 167 168 169 170 171 172 173 174
        break;

    case StopCalibrationCancelled:
        emit resetStatusTextArea();
        _hideAllCalAreas();
        break;

    default:
        // Assume failed
        _hideAllCalAreas();
175
        qgcApp()->showMessage(QStringLiteral("Calibration failed. Calibration log will be displayed."));
176
        break;
Don Gagne's avatar
Don Gagne committed
177 178 179 180 181 182 183 184 185
    }
    
    _magCalInProgress = false;
    _accelCalInProgress = false;
}

void APMSensorsComponentController::calibrateCompass(void)
{
    _startLogCalibration();
186
    _compassCal.startCalibration();
Don Gagne's avatar
Don Gagne committed
187 188 189 190
}

void APMSensorsComponentController::calibrateAccel(void)
{
191
    _vehicle->setConnectionLostEnabled(false);
Don Gagne's avatar
Don Gagne committed
192
    _startLogCalibration();
193
    _accelCalInProgress = true;
Don Gagne's avatar
Don Gagne committed
194 195 196 197 198 199 200 201 202 203 204 205 206 207
    _uas->startCalibration(UASInterface::StartCalibrationAccel);
}

void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
{
    Q_UNUSED(compId);
    Q_UNUSED(severity);
    
    UASInterface* uas = _autopilot->vehicle()->uas();
    Q_ASSERT(uas);
    if (uasId != uas->getUASID()) {
        return;
    }

208 209
    if (text.startsWith(QLatin1Literal("PreArm:")) || text.startsWith(QLatin1Literal("EKF"))
            || text.startsWith(QLatin1Literal("Arm")) || text.startsWith(QLatin1Literal("Initialising"))) {
Don Gagne's avatar
Don Gagne committed
210 211 212
        return;
    }

213
    if (text.contains(QLatin1Literal("progress <"))) {
214 215 216 217 218 219 220 221 222 223
        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;
    }

224
    QString anyKey(QStringLiteral("and press any"));
Don Gagne's avatar
Don Gagne committed
225
    if (text.contains(anyKey)) {
226
        text = text.left(text.indexOf(anyKey)) + QStringLiteral("and click Next to continue.");
227
        _nextButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
228 229 230 231 232
    }

    _appendStatusLog(text);
    qCDebug(APMSensorsComponentControllerLog) << text << severity;

233
    if (text.contains(QLatin1String("Calibration successful"))) {
Don Gagne's avatar
Don Gagne committed
234 235 236 237
        _stopCalibration(StopCalibrationSuccess);
        return;
    }

238
    if (text.contains(QLatin1String("FAILED"))) {
Don Gagne's avatar
Don Gagne committed
239 240 241 242 243
        _stopCalibration(StopCalibrationFailed);
        return;
    }

    // All calibration messages start with [cal]
244
    QString calPrefix(QStringLiteral("[cal] "));
Don Gagne's avatar
Don Gagne committed
245 246 247 248 249
    if (!text.startsWith(calPrefix)) {
        return;
    }
    text = text.right(text.length() - calPrefix.length());

250
    QString calStartPrefix(QStringLiteral("calibration started: "));
Don Gagne's avatar
Don Gagne committed
251 252 253 254 255
    if (text.startsWith(calStartPrefix)) {
        text = text.right(text.length() - calStartPrefix.length());
        
        _startVisualCalibration();
        
256
        if (text == QLatin1Literal("accel") || text == QLatin1Literal("mag") || text == QLatin1Literal("gyro")) {
Don Gagne's avatar
Don Gagne committed
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 305 306 307
            // 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;
                _orientationCalUpsideDownSideVisible = true;
                _orientationCalLeftSideVisible = true;
                _orientationCalRightSideVisible = true;
                _orientationCalTailDownSideVisible = true;
                _orientationCalNoseDownSideVisible = true;
            } else {
                Q_ASSERT(false);
            }
            emit orientationCalSidesDoneChanged();
            emit orientationCalSidesVisibleChanged();
            emit orientationCalSidesInProgressChanged();
            _updateAndEmitShowOrientationCalArea(true);
        }
        return;
    }
    
308
    if (text.endsWith(QLatin1Literal("orientation detected"))) {
Don Gagne's avatar
Don Gagne committed
309 310 311
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side started" << side;
        
312
        if (side == QLatin1Literal("down")) {
Don Gagne's avatar
Don Gagne committed
313 314 315 316
            _orientationCalDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalDownSideRotate = true;
            }
317
        } else if (side == QLatin1Literal("up")) {
Don Gagne's avatar
Don Gagne committed
318 319 320 321
            _orientationCalUpsideDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalUpsideDownSideRotate = true;
            }
322
        } else if (side == QLatin1Literal("left")) {
Don Gagne's avatar
Don Gagne committed
323 324 325 326
            _orientationCalLeftSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalLeftSideRotate = true;
            }
327
        } else if (side == QLatin1Literal("right")) {
Don Gagne's avatar
Don Gagne committed
328 329 330 331
            _orientationCalRightSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalRightSideRotate = true;
            }
332
        } else if (side == QLatin1Literal("front")) {
Don Gagne's avatar
Don Gagne committed
333 334 335 336
            _orientationCalNoseDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalNoseDownSideRotate = true;
            }
337
        } else if (side == QLatin1Literal("back")) {
Don Gagne's avatar
Don Gagne committed
338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354
            _orientationCalTailDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalTailDownSideRotate = true;
            }
        }
        
        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");
        }
        
        emit orientationCalSidesInProgressChanged();
        emit orientationCalSidesRotateChanged();
        return;
    }
    
355
    if (text.endsWith(QLatin1Literal("side done, rotate to a different side"))) {
Don Gagne's avatar
Don Gagne committed
356 357 358
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side finished" << side;
        
359
        if (side == QLatin1Literal("down")) {
Don Gagne's avatar
Don Gagne committed
360 361 362
            _orientationCalDownSideInProgress = false;
            _orientationCalDownSideDone = true;
            _orientationCalDownSideRotate = false;
363
        } else if (side == QLatin1Literal("up")) {
Don Gagne's avatar
Don Gagne committed
364 365
            _orientationCalUpsideDownSideInProgress = false;
            _orientationCalUpsideDownSideDone = true;
366
            _orientationCalUpsideDownSideRotate = false;
367
        } else if (side == QLatin1Literal("left")) {
Don Gagne's avatar
Don Gagne committed
368 369 370
            _orientationCalLeftSideInProgress = false;
            _orientationCalLeftSideDone = true;
            _orientationCalLeftSideRotate = false;
371
        } else if (side == QLatin1Literal("right")) {
Don Gagne's avatar
Don Gagne committed
372 373
            _orientationCalRightSideInProgress = false;
            _orientationCalRightSideDone = true;
374
            _orientationCalRightSideRotate = false;
375
        } else if (side == QLatin1Literal("front")) {
Don Gagne's avatar
Don Gagne committed
376 377 378
            _orientationCalNoseDownSideInProgress = false;
            _orientationCalNoseDownSideDone = true;
            _orientationCalNoseDownSideRotate = false;
379
        } else if (side == QLatin1Literal("back")) {
Don Gagne's avatar
Don Gagne committed
380 381
            _orientationCalTailDownSideInProgress = false;
            _orientationCalTailDownSideDone = true;
382
            _orientationCalTailDownSideRotate = false;
Don Gagne's avatar
Don Gagne committed
383 384 385 386 387 388 389 390 391 392
        }
        
        _orientationCalAreaHelpText->setProperty("text", "Place you vehicle into one of the orientations shown below and hold it still");

        emit orientationCalSidesInProgressChanged();
        emit orientationCalSidesDoneChanged();
        emit orientationCalSidesRotateChanged();
        return;
    }
    
393
    if (text.startsWith(QLatin1Literal("calibration done:"))) {
394 395 396 397
        _stopCalibration(StopCalibrationSuccess);
        return;
    }

398
    if (text.startsWith(QLatin1Literal("calibration cancelled"))) {
Don Gagne's avatar
Don Gagne committed
399 400 401 402
        _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
        return;
    }

403
    if (text.startsWith(QLatin1Literal("calibration failed"))) {
404 405 406
        _stopCalibration(StopCalibrationFailed);
        return;
    }
Don Gagne's avatar
Don Gagne committed
407 408 409 410 411 412
}

void APMSensorsComponentController::_refreshParams(void)
{
    QStringList fastRefreshList;
    
413 414
    fastRefreshList << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X")
                    << QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z");
415
    foreach (const QString &paramName, fastRefreshList) {
Don Gagne's avatar
Don Gagne committed
416 417 418 419
        _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName);
    }
    
    // Now ask for all to refresh
420 421
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_"));
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
Don Gagne's avatar
Don Gagne committed
422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439
}

void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
{
    _showOrientationCalArea = show;
    emit showOrientationCalAreaChanged();
}

void APMSensorsComponentController::_hideAllCalAreas(void)
{
    _updateAndEmitShowOrientationCalArea(false);
}

void APMSensorsComponentController::cancelCalibration(void)
{
    _waitingForCancel = true;
    emit waitingForCancelChanged();
    _cancelButton->setEnabled(false);
440 441 442 443 444 445 446 447

    if (_magCalInProgress) {
        _compassCal.cancelCalibration();
    } else {
        // The firmware doesn't always allow us to cancel calibration. The best we can do is wait
        // for it to timeout.
        _uas->stopCalibration();
    }
Don Gagne's avatar
Don Gagne committed
448 449 450 451 452 453 454 455 456 457 458 459 460
}

void APMSensorsComponentController::nextClicked(void)
{
    mavlink_message_t       msg;
    mavlink_command_ack_t   ack;

    ack.command = 0;
    ack.result = 1;
    mavlink_msg_command_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &msg, &ack);

    _vehicle->sendMessage(msg);
}
461 462 463 464 465 466 467 468 469 470

bool APMSensorsComponentController::compassSetupNeeded(void) const
{
    return _sensorsComponent->compassSetupNeeded();
}

bool APMSensorsComponentController::accelSetupNeeded(void) const
{
    return _sensorsComponent->accelSetupNeeded();
}
Don Gagne's avatar
Don Gagne committed
471 472 473 474 475

bool APMSensorsComponentController::usingUDPLink(void)
{
    return _vehicle->priorityLink()->getLinkConfiguration()->type() == LinkConfiguration::TypeUdp;
}