SensorsComponentController.cc 13.4 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 35 36

#include <QVariant>
#include <QQmlProperty>

SensorsComponentController::SensorsComponentController(AutoPilotPlugin* autopilot, QObject* parent) :
    QObject(parent),
37 38 39
    _statusLog(NULL),
    _progressBar(NULL),
    _showGyroCalArea(false),
Don Gagne's avatar
Don Gagne committed
40
    _showOrientationCalArea(false),
41 42 43
    _showCompass0(false),
    _showCompass1(false),
    _showCompass2(false),
44
    _gyroCalInProgress(false),
Don Gagne's avatar
Don Gagne committed
45 46 47 48 49 50 51 52 53 54 55 56 57 58
    _magCalInProgress(false),
    _accelCalInProgress(false),
    _orientationCalDownSideDone(false),
    _orientationCalUpsideDownSideDone(false),
    _orientationCalLeftSideDone(false),
    _orientationCalRightSideDone(false),
    _orientationCalNoseDownSideDone(false),
    _orientationCalTailDownSideDone(false),
    _orientationCalDownSideInProgress(false),
    _orientationCalUpsideDownSideInProgress(false),
    _orientationCalLeftSideInProgress(false),
    _orientationCalRightSideInProgress(false),
    _orientationCalNoseDownSideInProgress(false),
    _orientationCalTailDownSideInProgress(false),
59
    _textLoggingStarted(false),
Don Gagne's avatar
Don Gagne committed
60 61
    _autopilot(autopilot)
{
62 63 64 65 66 67 68 69 70 71
    Q_ASSERT(_autopilot);
    Q_ASSERT(_autopilot->pluginReady());
    
    // Mag rotation parameters are optional
    _showCompass0 = _autopilot->parameterExists("CAL_MAG0_ROT") &&
                        _autopilot->getParameterFact("CAL_MAG0_ROT")->value().toInt() >= 0;
    _showCompass1 = _autopilot->parameterExists("CAL_MAG1_ROT") &&
                        _autopilot->getParameterFact("CAL_MAG1_ROT")->value().toInt() >= 0;
    _showCompass2 = _autopilot->parameterExists("CAL_MAG2_ROT") &&
                        _autopilot->getParameterFact("CAL_MAG2_ROT")->value().toInt() >= 0;
Don Gagne's avatar
Don Gagne committed
72 73 74 75 76 77 78 79 80 81 82 83 84 85 86
}

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

87
void SensorsComponentController::_startCalibration(void)
Don Gagne's avatar
Don Gagne committed
88 89
{
    _beginTextLogging();
90 91 92 93 94 95 96 97 98 99
    _hideAllCalAreas();
    
    _compassButton->setEnabled(false);
    _gyroButton->setEnabled(false);
    _accelButton->setEnabled(false);
    _airspeedButton->setEnabled(false);
}

void SensorsComponentController::_stopCalibration(bool failed)
{
Don Gagne's avatar
Don Gagne committed
100 101 102
    _magCalInProgress = false;
    _accelCalInProgress = false;
    
103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120
    _compassButton->setEnabled(true);
    _gyroButton->setEnabled(true);
    _accelButton->setEnabled(true);
    _airspeedButton->setEnabled(true);
    
    _progressBar->setProperty("value", failed ? 0 : 1);
    _updateAndEmitGyroCalInProgress(false);
    _refreshParams();
    
    if (failed) {
        QGCMessageBox::warning("Calibration", "Calibration failed. Calibration log will be displayed.");
        _hideAllCalAreas();
    }
}

void SensorsComponentController::calibrateGyro(void)
{
    _startCalibration();
Don Gagne's avatar
Don Gagne committed
121 122 123 124 125 126 127 128
    
    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
}

void SensorsComponentController::calibrateCompass(void)
{
129
    _startCalibration();
Don Gagne's avatar
Don Gagne committed
130 131 132 133 134 135 136 137

    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
}

void SensorsComponentController::calibrateAccel(void)
{
138
    _startCalibration();
Don Gagne's avatar
Don Gagne committed
139 140 141 142 143 144 145 146

    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0);
}

void SensorsComponentController::calibrateAirspeed(void)
{
147
    _startCalibration();
Don Gagne's avatar
Don Gagne committed
148 149 150 151 152 153 154 155

    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0);
}

void SensorsComponentController::_beginTextLogging(void)
{
156 157 158 159 160 161
    if (!_textLoggingStarted) {
        _textLoggingStarted = true;
        UASInterface* uas = _autopilot->uas();
        Q_ASSERT(uas);
        connect(uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
    }
Don Gagne's avatar
Don Gagne committed
162 163 164 165
}

void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
{
166 167
    QString startingSidePrefix("Hold still, starting to measure ");
    QString sideDoneSuffix(" side done, rotate to a different side");
Don Gagne's avatar
Don Gagne committed
168
    QString orientationDetectedSuffix(" orientation detected");
169
    
Don Gagne's avatar
Don Gagne committed
170 171 172 173 174 175 176 177 178 179
    Q_UNUSED(compId);
    Q_UNUSED(severity);
    
    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    if (uasId != uas->getUASID()) {
        return;
    }
    
    QStringList ignorePrefixList;
180
    ignorePrefixList << "[cmd]" << "[mavlink pm]" << "[ekf check]" << "[pm]" << "[inav]" << "IN AIR MODE" << "LANDED MODE";
Don Gagne's avatar
Don Gagne committed
181 182 183 184 185 186
    foreach (QString ignorePrefix, ignorePrefixList) {
        if (text.startsWith(ignorePrefix)) {
            return;
        }
    }
    
187 188 189 190 191 192 193 194 195 196 197
    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
198
    _appendStatusLog(text);
199 200 201 202

    if (text == "gyro calibration: started") {
        _updateAndEmitShowGyroCalArea(true);
        _updateAndEmitGyroCalInProgress(true);
Don Gagne's avatar
Don Gagne committed
203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225
    } else if (text == "accel calibration: started" || text == "mag calibration: started") {
        if (text == "accel calibration: started") {
            _accelCalInProgress = true;
            _updateAndEmitCalInProgressText("Hold Still");
        } else {
            _updateAndEmitCalInProgressText("Rotate");
            _magCalInProgress = true;
        }
        _orientationCalDownSideDone = false;
        _orientationCalUpsideDownSideDone = false;
        _orientationCalLeftSideDone = false;
        _orientationCalRightSideDone = false;
        _orientationCalTailDownSideDone = false;
        _orientationCalNoseDownSideDone = false;
        _orientationCalDownSideInProgress = false;
        _orientationCalUpsideDownSideInProgress = false;
        _orientationCalLeftSideInProgress = false;
        _orientationCalRightSideInProgress = false;
        _orientationCalNoseDownSideInProgress = false;
        _orientationCalTailDownSideInProgress = false;
        emit orientationCalSidesDoneChanged();
        emit orientationCalSidesInProgressChanged();
        _updateAndEmitShowOrientationCalArea(true);
226 227 228 229
    } else if (text.startsWith(startingSidePrefix)) {
        QString side = text.right(text.length() - startingSidePrefix.length()).section(" ", 0, 0);
        qDebug() << "Side started" << side;
        if (side == "down") {
Don Gagne's avatar
Don Gagne committed
230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247
            _orientationCalDownSideInProgress = true;
        } else if (side == "up") {
            _orientationCalUpsideDownSideInProgress = true;
        } else if (side == "left") {
            _orientationCalLeftSideInProgress = true;
        } else if (side == "right") {
            _orientationCalRightSideInProgress = true;
        } else if (side == "front") {
            _orientationCalNoseDownSideInProgress = true;
        } else if (side == "back") {
            _orientationCalTailDownSideInProgress = true;
        }
        emit orientationCalSidesInProgressChanged();
    } else if (text.endsWith(orientationDetectedSuffix)) {
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side started" << side;
        if (side == "down") {
            _orientationCalDownSideInProgress = true;
248
        } else if (side == "up") {
Don Gagne's avatar
Don Gagne committed
249
            _orientationCalUpsideDownSideInProgress = true;
250
        } else if (side == "left") {
Don Gagne's avatar
Don Gagne committed
251
            _orientationCalLeftSideInProgress = true;
252
        } else if (side == "right") {
Don Gagne's avatar
Don Gagne committed
253
            _orientationCalRightSideInProgress = true;
254
        } else if (side == "front") {
Don Gagne's avatar
Don Gagne committed
255
            _orientationCalNoseDownSideInProgress = true;
256
        } else if (side == "back") {
Don Gagne's avatar
Don Gagne committed
257
            _orientationCalTailDownSideInProgress = true;
258
        }
Don Gagne's avatar
Don Gagne committed
259
        emit orientationCalSidesInProgressChanged();
260 261 262 263
    } else if (text.endsWith(sideDoneSuffix)) {
        QString side = text.section(" ", 0, 0);
        qDebug() << "Side finished" << side;
        if (side == "down") {
Don Gagne's avatar
Don Gagne committed
264 265
            _orientationCalDownSideInProgress = false;
            _orientationCalDownSideDone = true;
266
        } else if (side == "up") {
Don Gagne's avatar
Don Gagne committed
267 268
            _orientationCalUpsideDownSideInProgress = false;
            _orientationCalUpsideDownSideDone = true;
269
        } else if (side == "left") {
Don Gagne's avatar
Don Gagne committed
270 271
            _orientationCalLeftSideInProgress = false;
            _orientationCalLeftSideDone = true;
272
        } else if (side == "right") {
Don Gagne's avatar
Don Gagne committed
273 274
            _orientationCalRightSideInProgress = false;
            _orientationCalRightSideDone = true;
275
        } else if (side == "front") {
Don Gagne's avatar
Don Gagne committed
276 277
            _orientationCalNoseDownSideInProgress = false;
            _orientationCalNoseDownSideDone = true;
278
        } else if (side == "back") {
Don Gagne's avatar
Don Gagne committed
279 280
            _orientationCalTailDownSideInProgress = false;
            _orientationCalTailDownSideDone = true;
281
        }
Don Gagne's avatar
Don Gagne committed
282 283 284
        emit orientationCalSidesInProgressChanged();
        emit orientationCalSidesDoneChanged();
    } else if (text == "accel calibration: done" || text == "mag calibration: done") {
285
        _progressBar->setProperty("value", 1);
Don Gagne's avatar
Don Gagne committed
286 287 288 289 290 291 292 293 294 295 296 297 298 299
        _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();
300
        _stopCalibration(false /* success */);
301
    } else if (text == "gyro calibration: done") {
302
        _stopCalibration(false /* success */);
Don Gagne's avatar
Don Gagne committed
303
    } else if (text == "dpress calibration: done") {
304
        _stopCalibration(false /* success */);
305
    } else if (text.endsWith(" calibration: failed")) {
306
        _stopCalibration(true /* failed */);
307
    }
Don Gagne's avatar
Don Gagne committed
308 309 310 311
}

void SensorsComponentController::_refreshParams(void)
{
Don Gagne's avatar
Don Gagne committed
312
    // Pull specified params first so red/green indicators update quickly
313 314 315 316
    _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG0_ID");
    _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_GYRO0_ID");
    _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_ACC0_ID");
    _autopilot->refreshParameter(FactSystem::defaultComponentId, "SENS_DPRES_OFF");
317
    
318
    _autopilot->refreshParameter(FactSystem::defaultComponentId, "SENS_BOARD_ROT");
Don Gagne's avatar
Don Gagne committed
319
    
320 321 322 323 324 325 326 327 328 329 330
    // Mag rotation parameters are optional
    if (_autopilot->parameterExists("CAL_MAG0_ROT")) {
        _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG0_ROT");
    }
    if (_autopilot->parameterExists("CAL_MAG1_ROT")) {
        _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG1_ROT");
    }
    if (_autopilot->parameterExists("CAL_MAG2_ROT")) {
        _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG2_ROT");
    }
    
Don Gagne's avatar
Don Gagne committed
331 332
    // Pull full set in order to get all cal values back
    _autopilot->refreshAllParameters();
Don Gagne's avatar
Don Gagne committed
333 334 335 336 337 338 339 340
}

bool SensorsComponentController::fixedWing(void)
{
    UASInterface* uas = _autopilot->uas();
    Q_ASSERT(uas);
    return uas->getSystemType() == MAV_TYPE_FIXED_WING;
}
341 342 343 344 345 346 347 348 349 350 351 352 353

void SensorsComponentController::_updateAndEmitGyroCalInProgress(bool inProgress)
{
    _gyroCalInProgress = inProgress;
    emit gyroCalInProgressChanged();
}

void SensorsComponentController::_updateAndEmitShowGyroCalArea(bool show)
{
    _showGyroCalArea = show;
    emit showGyroCalAreaChanged();
}

Don Gagne's avatar
Don Gagne committed
354
void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
355
{
Don Gagne's avatar
Don Gagne committed
356 357
    _showOrientationCalArea = show;
    emit showOrientationCalAreaChanged();
358 359 360 361 362
}

void SensorsComponentController::_hideAllCalAreas(void)
{
    _updateAndEmitShowGyroCalArea(false);
Don Gagne's avatar
Don Gagne committed
363 364 365 366 367 368 369
    _updateAndEmitShowOrientationCalArea(false);
}

void SensorsComponentController::_updateAndEmitCalInProgressText(const QString& text)
{
    _calInProgressText = text;
    emit calInProgressTextChanged(text);
370
}