APMSensorsComponentController.cc 17.8 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

#include <QVariant>
#include <QQmlProperty>

QGC_LOGGING_CATEGORY(APMSensorsComponentControllerLog, "APMSensorsComponentControllerLog")

APMSensorsComponentController::APMSensorsComponentController(void) :
    _statusLog(NULL),
    _progressBar(NULL),
    _compassButton(NULL),
    _accelButton(NULL),
27
    _compassMotButton(NULL),
Don Gagne's avatar
Don Gagne committed
28 29
    _nextButton(NULL),
    _cancelButton(NULL),
Don Gagne's avatar
Don Gagne committed
30
    _setOrientationsButton(NULL),
Don Gagne's avatar
Don Gagne committed
31 32 33
    _showOrientationCalArea(false),
    _magCalInProgress(false),
    _accelCalInProgress(false),
34
    _compassMotCalInProgress(false),
Don Gagne's avatar
Don Gagne committed
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
    _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)
{
61 62 63
    _compassCal.setVehicle(_vehicle);
    connect(&_compassCal, &APMCompassCal::vehicleTextMessage, this, &APMSensorsComponentController::_handleUASTextMessage);

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

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

/// 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);
91
    _compassMotButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
92
    _setOrientationsButton->setEnabled(false);
93
    if (_accelCalInProgress || _compassMotCalInProgress) {
94 95
        _nextButton->setEnabled(true);
    }
Don Gagne's avatar
Don Gagne committed
96 97 98 99 100 101 102
    _cancelButton->setEnabled(false);
}

void APMSensorsComponentController::_startVisualCalibration(void)
{
    _compassButton->setEnabled(false);
    _accelButton->setEnabled(false);
103
    _compassMotButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
104
    _setOrientationsButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
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
    _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)
{
140
    _vehicle->setConnectionLostEnabled(true);
141

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

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

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

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

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

void APMSensorsComponentController::calibrateCompass(void)
{
    _startLogCalibration();
190
    _compassCal.startCalibration();
Don Gagne's avatar
Don Gagne committed
191 192 193 194
}

void APMSensorsComponentController::calibrateAccel(void)
{
195
    _accelCalInProgress = true;
196
    _vehicle->setConnectionLostEnabled(false);
Don Gagne's avatar
Don Gagne committed
197 198 199 200
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAccel);
}

201 202 203 204 205 206 207 208 209 210 211
void APMSensorsComponentController::calibrateMotorInterference(void)
{
    _compassMotCalInProgress = true;
    _vehicle->setConnectionLostEnabled(false);
    _startLogCalibration();
    _appendStatusLog(tr("Raise the throttle slowly to between 50% ~ 75% (the props will spin!) for 5 ~ 10 seconds."));
    _appendStatusLog(tr("Quickly bring the throttle back down to zero"));
    _appendStatusLog(tr("Press the Next button to complete the calibration"));
    _uas->startCalibration(UASInterface::StartCalibrationCompassMot);
}

Don Gagne's avatar
Don Gagne committed
212 213 214 215 216 217 218 219 220 221 222
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;
    }

223 224
    if (text.startsWith(QLatin1Literal("PreArm:")) || text.startsWith(QLatin1Literal("EKF"))
            || text.startsWith(QLatin1Literal("Arm")) || text.startsWith(QLatin1Literal("Initialising"))) {
Don Gagne's avatar
Don Gagne committed
225 226 227
        return;
    }

228
    if (text.contains(QLatin1Literal("progress <"))) {
229 230 231 232 233 234 235 236 237 238
        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;
    }

239
    QString anyKey(QStringLiteral("and press any"));
Don Gagne's avatar
Don Gagne committed
240
    if (text.contains(anyKey)) {
241
        text = text.left(text.indexOf(anyKey)) + QStringLiteral("and click Next to continue.");
242
        _nextButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
243 244 245 246 247
    }

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

248
    if (text.contains(QLatin1String("Calibration successful"))) {
Don Gagne's avatar
Don Gagne committed
249 250 251 252
        _stopCalibration(StopCalibrationSuccess);
        return;
    }

253
    if (text.contains(QLatin1String("FAILED"))) {
Don Gagne's avatar
Don Gagne committed
254 255 256 257 258
        _stopCalibration(StopCalibrationFailed);
        return;
    }

    // All calibration messages start with [cal]
259
    QString calPrefix(QStringLiteral("[cal] "));
Don Gagne's avatar
Don Gagne committed
260 261 262 263 264
    if (!text.startsWith(calPrefix)) {
        return;
    }
    text = text.right(text.length() - calPrefix.length());

265
    QString calStartPrefix(QStringLiteral("calibration started: "));
Don Gagne's avatar
Don Gagne committed
266 267 268 269 270
    if (text.startsWith(calStartPrefix)) {
        text = text.right(text.length() - calStartPrefix.length());
        
        _startVisualCalibration();
        
271
        if (text == QLatin1Literal("accel") || text == QLatin1Literal("mag") || text == QLatin1Literal("gyro")) {
Don Gagne's avatar
Don Gagne committed
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 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322
            // 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;
    }
    
323
    if (text.endsWith(QLatin1Literal("orientation detected"))) {
Don Gagne's avatar
Don Gagne committed
324 325 326
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side started" << side;
        
327
        if (side == QLatin1Literal("down")) {
Don Gagne's avatar
Don Gagne committed
328 329 330 331
            _orientationCalDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalDownSideRotate = true;
            }
332
        } else if (side == QLatin1Literal("up")) {
Don Gagne's avatar
Don Gagne committed
333 334 335 336
            _orientationCalUpsideDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalUpsideDownSideRotate = true;
            }
337
        } else if (side == QLatin1Literal("left")) {
Don Gagne's avatar
Don Gagne committed
338 339 340 341
            _orientationCalLeftSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalLeftSideRotate = true;
            }
342
        } else if (side == QLatin1Literal("right")) {
Don Gagne's avatar
Don Gagne committed
343 344 345 346
            _orientationCalRightSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalRightSideRotate = true;
            }
347
        } else if (side == QLatin1Literal("front")) {
Don Gagne's avatar
Don Gagne committed
348 349 350 351
            _orientationCalNoseDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalNoseDownSideRotate = true;
            }
352
        } else if (side == QLatin1Literal("back")) {
Don Gagne's avatar
Don Gagne committed
353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369
            _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;
    }
    
370
    if (text.endsWith(QLatin1Literal("side done, rotate to a different side"))) {
Don Gagne's avatar
Don Gagne committed
371 372 373
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side finished" << side;
        
374
        if (side == QLatin1Literal("down")) {
Don Gagne's avatar
Don Gagne committed
375 376 377
            _orientationCalDownSideInProgress = false;
            _orientationCalDownSideDone = true;
            _orientationCalDownSideRotate = false;
378
        } else if (side == QLatin1Literal("up")) {
Don Gagne's avatar
Don Gagne committed
379 380
            _orientationCalUpsideDownSideInProgress = false;
            _orientationCalUpsideDownSideDone = true;
381
            _orientationCalUpsideDownSideRotate = false;
382
        } else if (side == QLatin1Literal("left")) {
Don Gagne's avatar
Don Gagne committed
383 384 385
            _orientationCalLeftSideInProgress = false;
            _orientationCalLeftSideDone = true;
            _orientationCalLeftSideRotate = false;
386
        } else if (side == QLatin1Literal("right")) {
Don Gagne's avatar
Don Gagne committed
387 388
            _orientationCalRightSideInProgress = false;
            _orientationCalRightSideDone = true;
389
            _orientationCalRightSideRotate = false;
390
        } else if (side == QLatin1Literal("front")) {
Don Gagne's avatar
Don Gagne committed
391 392 393
            _orientationCalNoseDownSideInProgress = false;
            _orientationCalNoseDownSideDone = true;
            _orientationCalNoseDownSideRotate = false;
394
        } else if (side == QLatin1Literal("back")) {
Don Gagne's avatar
Don Gagne committed
395 396
            _orientationCalTailDownSideInProgress = false;
            _orientationCalTailDownSideDone = true;
397
            _orientationCalTailDownSideRotate = false;
Don Gagne's avatar
Don Gagne committed
398 399 400 401 402 403 404 405 406 407
        }
        
        _orientationCalAreaHelpText->setProperty("text", "Place you vehicle into one of the orientations shown below and hold it still");

        emit orientationCalSidesInProgressChanged();
        emit orientationCalSidesDoneChanged();
        emit orientationCalSidesRotateChanged();
        return;
    }
    
408
    if (text.startsWith(QLatin1Literal("calibration done:"))) {
409 410 411 412
        _stopCalibration(StopCalibrationSuccess);
        return;
    }

413
    if (text.startsWith(QLatin1Literal("calibration cancelled"))) {
Don Gagne's avatar
Don Gagne committed
414 415 416 417
        _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
        return;
    }

418
    if (text.startsWith(QLatin1Literal("calibration failed"))) {
419 420 421
        _stopCalibration(StopCalibrationFailed);
        return;
    }
Don Gagne's avatar
Don Gagne committed
422 423 424 425 426 427
}

void APMSensorsComponentController::_refreshParams(void)
{
    QStringList fastRefreshList;
    
428 429
    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");
430
    foreach (const QString &paramName, fastRefreshList) {
Don Gagne's avatar
Don Gagne committed
431 432 433 434
        _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName);
    }
    
    // Now ask for all to refresh
435 436
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_"));
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
Don Gagne's avatar
Don Gagne committed
437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454
}

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);
455 456 457 458 459 460 461 462

    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
463 464 465 466 467 468 469 470 471 472 473
}

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);

474
    _vehicle->sendMessageOnPriorityLink(msg);
475 476 477 478

    if (_compassMotCalInProgress) {
        _stopCalibration(StopCalibrationSuccess);
    }
Don Gagne's avatar
Don Gagne committed
479
}
480 481 482 483 484 485 486 487 488 489

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

bool APMSensorsComponentController::accelSetupNeeded(void) const
{
    return _sensorsComponent->accelSetupNeeded();
}
Don Gagne's avatar
Don Gagne committed
490 491 492 493 494

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