Skip to content
SensorsComponentController.cc 16.5 KiB
Newer Older
Don Gagne's avatar
Don Gagne committed
/*=====================================================================
 
 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 "QGCMessageBox.h"
#include "UAS.h"
Don Gagne's avatar
Don Gagne committed

#include <QVariant>
#include <QQmlProperty>

QGC_LOGGING_CATEGORY(SensorsComponentControllerLog, "SensorsComponentControllerLog")

Don Gagne's avatar
Don Gagne committed
SensorsComponentController::SensorsComponentController(void) :
    _statusLog(NULL),
    _progressBar(NULL),
Don Gagne's avatar
Don Gagne committed
    _compassButton(NULL),
    _gyroButton(NULL),
    _accelButton(NULL),
    _airspeedButton(NULL),
    _levelButton(NULL),
Don Gagne's avatar
Don Gagne committed
    _cancelButton(NULL),
Don Gagne's avatar
Don Gagne committed
    _showOrientationCalArea(false),
    _gyroCalInProgress(false),
Don Gagne's avatar
Don Gagne committed
    _magCalInProgress(false),
    _accelCalInProgress(false),
    _orientationCalDownSideDone(false),
    _orientationCalUpsideDownSideDone(false),
    _orientationCalLeftSideDone(false),
    _orientationCalRightSideDone(false),
    _orientationCalNoseDownSideDone(false),
    _orientationCalTailDownSideDone(false),
Don Gagne's avatar
Don Gagne committed
    _orientationCalDownSideVisible(false),
    _orientationCalUpsideDownSideVisible(false),
    _orientationCalLeftSideVisible(false),
    _orientationCalRightSideVisible(false),
    _orientationCalNoseDownSideVisible(false),
    _orientationCalTailDownSideVisible(false),
Don Gagne's avatar
Don Gagne committed
    _orientationCalDownSideInProgress(false),
    _orientationCalUpsideDownSideInProgress(false),
    _orientationCalLeftSideInProgress(false),
    _orientationCalRightSideInProgress(false),
    _orientationCalNoseDownSideInProgress(false),
    _orientationCalTailDownSideInProgress(false),
Don Gagne's avatar
Don Gagne committed
    _orientationCalDownSideRotate(false),
    _orientationCalUpsideDownSideRotate(false),
Don Gagne's avatar
Don Gagne committed
    _orientationCalLeftSideRotate(false),
    _orientationCalRightSideRotate(false),
Don Gagne's avatar
Don Gagne committed
    _orientationCalNoseDownSideRotate(false),
    _orientationCalTailDownSideRotate(false),
Don Gagne's avatar
Don Gagne committed
    _unknownFirmwareVersion(false),
Don Gagne's avatar
Don Gagne committed
    _waitingForCancel(false)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed

Don Gagne's avatar
Don Gagne committed
}

/// 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
void SensorsComponentController::_startLogCalibration(void)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    _unknownFirmwareVersion = false;
    _hideAllCalAreas();
    
Don Gagne's avatar
Don Gagne committed
    connect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
    
    _cancelButton->setEnabled(false);
}

void SensorsComponentController::_startVisualCalibration(void)
{
    _compassButton->setEnabled(false);
    _gyroButton->setEnabled(false);
    _accelButton->setEnabled(false);
    _airspeedButton->setEnabled(false);
    _levelButton->setEnabled(false);
Don Gagne's avatar
Don Gagne committed
    _cancelButton->setEnabled(true);

    _resetInternalState();
Don Gagne's avatar
Don Gagne committed
    
    _progressBar->setProperty("value", 0);
void SensorsComponentController::_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();
}

Don Gagne's avatar
Don Gagne committed
void SensorsComponentController::_stopCalibration(SensorsComponentController::StopCalibrationCode code)
Don Gagne's avatar
Don Gagne committed
    disconnect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
Don Gagne's avatar
Don Gagne committed
    
    _compassButton->setEnabled(true);
    _gyroButton->setEnabled(true);
    _accelButton->setEnabled(true);
    _airspeedButton->setEnabled(true);
    _levelButton->setEnabled(true);
Don Gagne's avatar
Don Gagne committed
    _cancelButton->setEnabled(false);
    
    if (code == StopCalibrationSuccess) {
        _resetInternalState();
Don Gagne's avatar
Don Gagne committed
        
        _progressBar->setProperty("value", 1);
    } else {
        _progressBar->setProperty("value", 0);
    }
Don Gagne's avatar
Don Gagne committed
    _waitingForCancel = false;
    emit waitingForCancelChanged();

Don Gagne's avatar
Don Gagne committed
    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;
Don Gagne's avatar
Don Gagne committed
    
    _magCalInProgress = false;
    _accelCalInProgress = false;
    _gyroCalInProgress = false;
}

void SensorsComponentController::calibrateGyro(void)
{
Don Gagne's avatar
Don Gagne committed
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationGyro);
Don Gagne's avatar
Don Gagne committed
}

void SensorsComponentController::calibrateCompass(void)
{
Don Gagne's avatar
Don Gagne committed
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationMag);
Don Gagne's avatar
Don Gagne committed
}

void SensorsComponentController::calibrateAccel(void)
{
Don Gagne's avatar
Don Gagne committed
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAccel);
void SensorsComponentController::calibrateLevel(void)
{
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationLevel);
}

Don Gagne's avatar
Don Gagne committed
void SensorsComponentController::calibrateAirspeed(void)
{
Don Gagne's avatar
Don Gagne committed
    _startLogCalibration();
    _uas->startCalibration(UASInterface::StartCalibrationAirspeed);
Don Gagne's avatar
Don Gagne committed
}

void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
{
    Q_UNUSED(compId);
    Q_UNUSED(severity);
    
    UASInterface* uas = _autopilot->vehicle()->uas();
Don Gagne's avatar
Don Gagne committed
    Q_ASSERT(uas);
    if (uasId != uas->getUASID()) {
        return;
    }
    
    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
    _appendStatusLog(text);
    qCDebug(SensorsComponentControllerLog) << text;
Don Gagne's avatar
Don Gagne committed
    
    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());
Don Gagne's avatar
Don Gagne committed
    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() != _supportedFirmwareCalVersion) {
Don Gagne's avatar
Don Gagne committed
            _unknownFirmwareVersion = true;
            QString msg = "Unsupported calibration firmware version, using log";
            _appendStatusLog(msg);
            qDebug() << msg;
Don Gagne's avatar
Don Gagne committed
            return;
Don Gagne's avatar
Don Gagne committed
        }
Don Gagne's avatar
Don Gagne committed
        
        _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;
                _orientationCalUpsideDownSideVisible = true;
Don Gagne's avatar
Don Gagne committed
                _orientationCalLeftSideVisible = true;
                _orientationCalRightSideVisible = true;
                _orientationCalTailDownSideVisible = true;
Don Gagne's avatar
Don Gagne committed
                _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
        }
Don Gagne's avatar
Don Gagne committed
        return;
    }
    
    if (text.endsWith("orientation detected")) {
Don Gagne's avatar
Don Gagne committed
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side started" << side;
Don Gagne's avatar
Don Gagne committed
        
Don Gagne's avatar
Don Gagne committed
        if (side == "down") {
            _orientationCalDownSideInProgress = true;
Don Gagne's avatar
Don Gagne committed
            if (_magCalInProgress) {
                _orientationCalDownSideRotate = true;
            }
        } else if (side == "up") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalUpsideDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalUpsideDownSideRotate = true;
            }
        } else if (side == "left") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalLeftSideInProgress = true;
Don Gagne's avatar
Don Gagne committed
            if (_magCalInProgress) {
                _orientationCalLeftSideRotate = true;
            }
        } else if (side == "right") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalRightSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalRightSideRotate = true;
            }
        } else if (side == "front") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalNoseDownSideInProgress = true;
Don Gagne's avatar
Don Gagne committed
            if (_magCalInProgress) {
                _orientationCalNoseDownSideRotate = true;
            }
        } else if (side == "back") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalTailDownSideInProgress = true;
            if (_magCalInProgress) {
                _orientationCalTailDownSideRotate = true;
            }
Don Gagne's avatar
Don Gagne committed
        
        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
        emit orientationCalSidesInProgressChanged();
Don Gagne's avatar
Don Gagne committed
        emit orientationCalSidesRotateChanged();
        return;
    }
    
    if (text.endsWith("side done, rotate to a different side")) {
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side finished" << side;
Don Gagne's avatar
Don Gagne committed
        
        if (side == "down") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalDownSideInProgress = false;
            _orientationCalDownSideDone = true;
Don Gagne's avatar
Don Gagne committed
            _orientationCalDownSideRotate = false;
        } else if (side == "up") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalUpsideDownSideInProgress = false;
            _orientationCalUpsideDownSideDone = true;
        } else if (side == "left") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalLeftSideInProgress = false;
            _orientationCalLeftSideDone = true;
Don Gagne's avatar
Don Gagne committed
            _orientationCalLeftSideRotate = false;
        } else if (side == "right") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalRightSideInProgress = false;
            _orientationCalRightSideDone = true;
        } else if (side == "front") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalNoseDownSideInProgress = false;
            _orientationCalNoseDownSideDone = true;
Don Gagne's avatar
Don Gagne committed
            _orientationCalNoseDownSideRotate = false;
        } else if (side == "back") {
Don Gagne's avatar
Don Gagne committed
            _orientationCalTailDownSideInProgress = false;
            _orientationCalTailDownSideDone = true;
Don Gagne's avatar
Don Gagne committed
        
        _orientationCalAreaHelpText->setProperty("text", "Place you vehicle into one of the orientations shown below and hold it still");

Don Gagne's avatar
Don Gagne committed
        emit orientationCalSidesInProgressChanged();
        emit orientationCalSidesDoneChanged();
Don Gagne's avatar
Don Gagne committed
        emit orientationCalSidesRotateChanged();
        return;
Don Gagne's avatar
Don Gagne committed
    QString calCompletePrefix("calibration done:");
    if (text.startsWith(calCompletePrefix)) {
        _stopCalibration(StopCalibrationSuccess);
        return;
Don Gagne's avatar
Don Gagne committed
    
    if (text.startsWith("calibration cancelled")) {
        _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
        return;
Don Gagne's avatar
Don Gagne committed
    if (text.startsWith("calibration failed")) {
        _stopCalibration(StopCalibrationFailed);
        return;
    }
}

void SensorsComponentController::_refreshParams(void)
{
Don Gagne's avatar
Don Gagne committed
    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
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_");
    _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_");
Don Gagne's avatar
Don Gagne committed
}

bool SensorsComponentController::fixedWing(void)
{
    UASInterface* uas = _autopilot->vehicle()->uas();
Don Gagne's avatar
Don Gagne committed
    Q_ASSERT(uas);
    return uas->getSystemType() == MAV_TYPE_FIXED_WING ||
            uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
            uas->getSystemType() == MAV_TYPE_VTOL_QUADROTOR ||
            uas->getSystemType() == MAV_TYPE_VTOL_TILTROTOR;
Don Gagne's avatar
Don Gagne committed
void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
Don Gagne's avatar
Don Gagne committed
    _showOrientationCalArea = show;
    emit showOrientationCalAreaChanged();
}

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

Don Gagne's avatar
Don Gagne committed
void SensorsComponentController::cancelCalibration(void)
Don Gagne's avatar
Don Gagne committed
{
Don Gagne's avatar
Don Gagne committed
    // 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();