QGCPX4SensorCalibration.cc 19 KB
Newer Older
1 2 3 4 5
#include "QGCPX4SensorCalibration.h"
#include "ui_QGCPX4SensorCalibration.h"
#include <UASManager.h>
#include <QMenu>
#include <QScrollBar>
6
#include <QDebug>
7 8 9 10 11 12 13 14 15 16

QGCPX4SensorCalibration::QGCPX4SensorCalibration(QWidget *parent) :
    QWidget(parent),
    activeUAS(NULL),
    clearAction(new QAction(tr("Clear Text"), this)),
    ui(new Ui::QGCPX4SensorCalibration)
{
    ui->setupUi(this);
    connect(clearAction, SIGNAL(triggered()), ui->textView, SLOT(clear()));

17 18 19
    connect(ui->gyroButton, SIGNAL(clicked()), this, SLOT(gyroButtonClicked()));
    connect(ui->magButton, SIGNAL(clicked()), this, SLOT(magButtonClicked()));
    connect(ui->accelButton, SIGNAL(clicked()), this, SLOT(accelButtonClicked()));
20
    connect(ui->diffPressureButton, SIGNAL(clicked()), this, SLOT(diffPressureButtonClicked()));
21 22 23 24 25

    ui->gyroButton->setEnabled(false);
    ui->magButton->setEnabled(false);
    ui->accelButton->setEnabled(false);

26 27 28
    ui->autopilotComboBox->setEnabled(false);
    ui->magComboBox->setEnabled(false);

Lorenz Meier's avatar
Lorenz Meier committed
29
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
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 59
    setAutopilotImage(":/files/images/px4/calibration/accel_z-.png");
    setGpsImage(":/files/images/px4/calibration/accel_z-.png");

    // Fill combo boxes
    ui->autopilotComboBox->addItem(tr("Default Orientation"), 0);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_45"), 1);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_90"), 2);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_135"), 3);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_180"), 4);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_225"), 5);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_270"), 6);
    ui->autopilotComboBox->addItem(tr("ROTATION_YAW_315"), 7);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180"), 8);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_YAW_45"), 9);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_YAW_90"), 10);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_YAW_135"), 11);
    ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_180"), 12);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_YAW_225"), 13);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_YAW_270"), 14);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_YAW_315"), 15);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90"), 16);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_YAW_45"), 17);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_YAW_90"), 18);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_YAW_135"), 19);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270"), 20);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_YAW_45"), 21);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_YAW_90"), 22);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_YAW_135"), 23);
    ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_90"), 24);
    ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_270"), 25);
60 61 62 63 64 65 66 67 68 69 70 71
    ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_180_YAW_90"), 26);
    ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_180_YAW_270"), 27);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_90"), 28);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_PITCH_90"), 29);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_PITCH_90"), 30);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_180"), 31);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_PITCH_180"), 32);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_270"), 33);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_PITCH_270"), 34);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_PITCH_270"), 35);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_180_YAW_90"), 36);
    ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_YAW_270"), 37);
72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98

    ui->magComboBox->addItem(tr("Default Orientation"), 0);
    ui->magComboBox->addItem(tr("ROTATION_YAW_45"), 1);
    ui->magComboBox->addItem(tr("ROTATION_YAW_90"), 2);
    ui->magComboBox->addItem(tr("ROTATION_YAW_135"), 3);
    ui->magComboBox->addItem(tr("ROTATION_YAW_180"), 4);
    ui->magComboBox->addItem(tr("ROTATION_YAW_225"), 5);
    ui->magComboBox->addItem(tr("ROTATION_YAW_270"), 6);
    ui->magComboBox->addItem(tr("ROTATION_YAW_315"), 7);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180"), 8);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180_YAW_45"), 9);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180_YAW_90"), 10);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180_YAW_135"), 11);
    ui->magComboBox->addItem(tr("ROTATION_PITCH_180"), 12);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180_YAW_225"), 13);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180_YAW_270"), 14);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_180_YAW_315"), 15);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_90"), 16);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_90_YAW_45"), 17);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_90_YAW_90"), 18);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_90_YAW_135"), 19);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_270"), 20);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_270_YAW_45"), 21);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_270_YAW_90"), 22);
    ui->magComboBox->addItem(tr("ROTATION_ROLL_270_YAW_135"), 23);
    ui->magComboBox->addItem(tr("ROTATION_PITCH_90"), 24);
    ui->magComboBox->addItem(tr("ROTATION_PITCH_270"), 25);
99 100 101 102 103 104 105

    setObjectName("PX4_SENSOR_CALIBRATION");

    setStyleSheet("QScrollArea { border: 0px; } QPlainTextEdit { border: 0px }");

    setActiveUAS(UASManager::instance()->getActiveUAS());
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
106
    ui->progressBar->setValue(0);
107 108 109 110

    connect(ui->autopilotComboBox, SIGNAL(activated(int)), this, SLOT(setAutopilotOrientation(int)));
    connect(ui->magComboBox, SIGNAL(activated(int)), this, SLOT(setGpsOrientation(int)));

Lorenz Meier's avatar
Lorenz Meier committed
111
    updateIcons();
112 113 114 115 116 117 118
}

QGCPX4SensorCalibration::~QGCPX4SensorCalibration()
{
    delete ui;
}

119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171
void QGCPX4SensorCalibration::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
    Q_UNUSED(uas);
    Q_UNUSED(component);

    int index = (int)value.toFloat();

    if (parameterName.contains("SENS_BOARD_ROT"))
    {
        ui->autopilotComboBox->setCurrentIndex(index);
        setAutopilotImage(index);
        ui->autopilotComboBox->setEnabled(true);
    }

    if (parameterName.contains("SENS_EXT_MAG_ROT"))
    {
        ui->magComboBox->setCurrentIndex(index);
        setGpsImage(index);
        ui->magComboBox->setEnabled(true);
    }

    // Check mag calibration naively
    if (parameterName.contains("SENS_MAG_XOFF")) {
        float offset = value.toFloat();
        if (offset < 0.000001f && offset > -0.000001f) {
            // Must be zero, not good
            setMagCalibrated(false);
        } else {
            setMagCalibrated(true);
        }
    }

    // Check gyro calibration naively
    if (parameterName.contains("SENS_GYRO_XOFF")) {
        float offset = value.toFloat();
        if (offset < 0.000001f && offset > -0.000001f) {
            // Must be zero, not good
            setGyroCalibrated(false);
        } else {
            setGyroCalibrated(true);
        }
    }

    // Check accel calibration naively
    if (parameterName.contains("SENS_ACC_XOFF")) {
        float offset = value.toFloat();
        if (offset < 0.000001f && offset > -0.000001f) {
            // Must be zero, not good
            setAccelCalibrated(false);
        } else {
            setAccelCalibrated(true);
        }
    }
172 173 174 175 176 177 178 179 180 181 182

    // Check differential pressure calibration naively
    if (parameterName.contains("SENS_DPRES_OFF")) {
      float offset = value.toFloat();
      if (offset < 0.000001f && offset > -0.000001f) {
          // Must be zero, not good
          setDiffPressureCalibrated(false);
      } else {
          setDiffPressureCalibrated(true);
      }
    }
183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229
}

void QGCPX4SensorCalibration::setMagCalibrated(bool calibrated)
{
    if (calibrated) {
        ui->magLabel->setText(tr("MAG CALIBRATED"));
        ui->magLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #20AA20;"
                                    "}");
    } else {
        ui->magLabel->setText(tr("MAG UNCALIBRATED"));
        ui->magLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #FF0037;"
                                    "}");
    }
}

void QGCPX4SensorCalibration::setGyroCalibrated(bool calibrated)
{
    if (calibrated) {
        ui->gyroLabel->setText(tr("GYRO CALIBRATED"));
        ui->gyroLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #20AA20;"
                                    "}");
    } else {
        ui->gyroLabel->setText(tr("GYRO UNCALIBRATED"));
        ui->gyroLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #FF0037;"
                                    "}");
    }
}

void QGCPX4SensorCalibration::setAccelCalibrated(bool calibrated)
{
    if (calibrated) {
        ui->accelLabel->setText(tr("ACCEL CALIBRATED"));
        ui->accelLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #20AA20;"
                                    "}");
    } else {
        ui->accelLabel->setText(tr("ACCEL UNCALIBRATED"));
        ui->accelLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #FF0037;"
                                    "}");
    }
}

230 231 232 233 234 235 236 237 238 239 240 241 242 243 244
void QGCPX4SensorCalibration::setDiffPressureCalibrated(bool calibrated)
{
    if (calibrated) {
        ui->diffPressureLabel->setText(tr("DIFF. PRESSURE CALIBRATED"));
        ui->diffPressureLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #20AA20;"
                                    "}");
    } else {
        ui->diffPressureLabel->setText(tr("DIFF. PRESSURE UNCALIBRATED"));
        ui->diffPressureLabel->setStyleSheet("QLabel { color: #FFFFFF;"
                                    "background-color: #FF0037;"
                                    "}");
    }
}

245 246 247 248 249 250 251
void QGCPX4SensorCalibration::setInstructionImage(const QString &path)
{
    instructionIcon.load(path);

    int w = ui->iconLabel->width();
    int h = ui->iconLabel->height();

252 253 254 255 256
    ui->iconLabel->setPixmap(instructionIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));
}

void QGCPX4SensorCalibration::setAutopilotImage(int index)
{
257
    setAutopilotImage(QString(":/files/images/px4/calibration/pixhawk_%1.png").arg(index, 2, 10, QChar('0')));
258 259 260 261
}

void QGCPX4SensorCalibration::setGpsImage(int index)
{
262
    setGpsImage(QString(":/files/images/px4/calibration/3dr_gps/gps_%1.png").arg(index, 2, 10, QChar('0')));
263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282
}

void QGCPX4SensorCalibration::setAutopilotOrientation(int index)
{
    if (activeUAS) {
        activeUAS->getParamManager()->setPendingParam(0, "SENS_BOARD_ROT", (int)index);
        activeUAS->getParamManager()->sendPendingParameters(true);
    }
}

void QGCPX4SensorCalibration::setGpsOrientation(int index)
{
    if (activeUAS) {
        activeUAS->getParamManager()->setPendingParam(0, "SENS_EXT_MAG_ROT", (int)index);
        activeUAS->getParamManager()->sendPendingParameters(true);
    }
}

void QGCPX4SensorCalibration::setAutopilotImage(const QString &path)
{
283 284 285
    if (autopilotIcon.load(path)) {
        int w = ui->autopilotLabel->width();
        int h = ui->autopilotLabel->height();
286

287 288 289 290
        ui->autopilotLabel->setPixmap(autopilotIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));
    } else {
        qDebug() << "AutoPilot Icon image did not load" << path;
    }
291 292 293 294
}

void QGCPX4SensorCalibration::setGpsImage(const QString &path)
{
295 296 297
    if (gpsIcon.load(path)) {
        int w = ui->gpsLabel->width();
        int h = ui->gpsLabel->height();
298

299 300 301 302
        ui->gpsLabel->setPixmap(gpsIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));
    } else {
        qDebug() << "GPS Icon image did not load" << path;
    }
303 304
}

Lorenz Meier's avatar
Lorenz Meier committed
305
void QGCPX4SensorCalibration::updateIcons()
306 307 308
{
    int w = ui->iconLabel->width();
    int h = ui->iconLabel->height();
309 310 311 312 313
    ui->iconLabel->setPixmap(instructionIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));

    int wa = ui->autopilotLabel->width();
    int ha = ui->autopilotLabel->height();
    ui->autopilotLabel->setPixmap(autopilotIcon.scaled(wa, ha, Qt::KeepAspectRatio, Qt::SmoothTransformation));
314

315 316 317
    int wg = ui->gpsLabel->width();
    int hg = ui->gpsLabel->height();
    ui->gpsLabel->setPixmap(gpsIcon.scaled(wg, hg, Qt::KeepAspectRatio, Qt::SmoothTransformation));
Lorenz Meier's avatar
Lorenz Meier committed
318
}
319

Lorenz Meier's avatar
Lorenz Meier committed
320 321 322
void QGCPX4SensorCalibration::resizeEvent(QResizeEvent* event)
{
    updateIcons();
323 324 325 326 327 328 329 330 331
    QWidget::resizeEvent(event);
}

void QGCPX4SensorCalibration::setActiveUAS(UASInterface* uas)
{
    if (!uas)
        return;

    if (activeUAS) {
332 333
        disconnect(activeUAS, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(handleTextMessage(int,int,int,QString)));
        disconnect(activeUAS, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
334 335 336
        ui->textView->clear();
    }

337 338 339 340
    ui->gyroButton->setEnabled(true);
    ui->magButton->setEnabled(true);
    ui->accelButton->setEnabled(true);

341
    connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(handleTextMessage(int,int,int,QString)));
342
    connect(uas, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
343
    activeUAS = uas;
344 345 346 347 348 349 350 351 352

    if (activeUAS->isRotaryWing()) {
        // Users are confused by the config button
        ui->diffPressureButton->hide();
        ui->diffPressureLabel->hide();
    } else {
        ui->diffPressureButton->show();
        ui->diffPressureLabel->show();
    }
353 354 355 356
}

void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int severity, QString text)
{
Lorenz Meier's avatar
Lorenz Meier committed
357 358 359 360
    Q_UNUSED(uasid);
    Q_UNUSED(compId);
    Q_UNUSED(severity);

361 362 363 364
    if (text.startsWith("[cmd]") ||
        text.startsWith("[mavlink pm]"))
        return;

Anton Babushkin's avatar
Anton Babushkin committed
365
    if (text.contains("progress <")) {
366 367 368 369 370 371 372 373
        QString percent = text.split("<").last().split(">").first();
        bool ok;
        int p = percent.toInt(&ok);
        if (ok)
            ui->progressBar->setValue(p);
        return;
    }

Lorenz Meier's avatar
Lorenz Meier committed
374 375
    ui->instructionLabel->setText(QString("%1").arg(text));

Anton Babushkin's avatar
Anton Babushkin committed
376 377 378
    if (text.startsWith("accel measurement started: ")) {
        QString axis = text.split("measurement started: ").last().left(2);
        setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis));
Lorenz Meier's avatar
Lorenz Meier committed
379 380
    }

Anton Babushkin's avatar
Anton Babushkin committed
381 382 383
    if (text.startsWith("directions left: ")) {
        QString axis = text.split("directions left: ").last().left(2);
        setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis));
384 385
    }

386 387
    if (text == "rotate in a figure 8 around all axis" /* support for old typo */
            || text == "rotate in a figure 8 around all axes" /* current version */) {
Lorenz Meier's avatar
Lorenz Meier committed
388
        setInstructionImage(":/files/images/px4/calibration/mag_calibration_figure8.png");
389 390
    }

Anton Babushkin's avatar
Anton Babushkin committed
391
    if (text.endsWith(" calibration: done") || text.endsWith(" calibration: failed")) {
392
        // XXX use a confirmation image or something
Lorenz Meier's avatar
Lorenz Meier committed
393
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
Anton Babushkin's avatar
Anton Babushkin committed
394 395 396 397
        if (text.endsWith(" calibration: done")) {
            ui->progressBar->setValue(100);
        } else {
            ui->progressBar->setValue(0);
398
        }
399

400
        if (activeUAS) {
Anton Babushkin's avatar
Anton Babushkin committed
401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427
            if (text.startsWith("accel ")) {
                activeUAS->requestParameter(0, "SENS_ACC_XOFF");
                activeUAS->requestParameter(0, "SENS_ACC_YOFF");
                activeUAS->requestParameter(0, "SENS_ACC_ZOFF");
                activeUAS->requestParameter(0, "SENS_ACC_XSCALE");
                activeUAS->requestParameter(0, "SENS_ACC_YSCALE");
                activeUAS->requestParameter(0, "SENS_ACC_ZSCALE");
                activeUAS->requestParameter(0, "SENS_BOARD_ROT");
            }
            if (text.startsWith("gyro ")) {
                activeUAS->requestParameter(0, "SENS_GYRO_XOFF");
                activeUAS->requestParameter(0, "SENS_GYRO_YOFF");
                activeUAS->requestParameter(0, "SENS_GYRO_ZOFF");
                activeUAS->requestParameter(0, "SENS_GYRO_XSCALE");
                activeUAS->requestParameter(0, "SENS_GYRO_YSCALE");
                activeUAS->requestParameter(0, "SENS_GYRO_ZSCALE");
                activeUAS->requestParameter(0, "SENS_BOARD_ROT");
            }
            if (text.startsWith("mag ")) {
                activeUAS->requestParameter(0, "SENS_MAG_XOFF");
                activeUAS->requestParameter(0, "SENS_MAG_YOFF");
                activeUAS->requestParameter(0, "SENS_MAG_ZOFF");
                activeUAS->requestParameter(0, "SENS_MAG_XSCALE");
                activeUAS->requestParameter(0, "SENS_MAG_YSCALE");
                activeUAS->requestParameter(0, "SENS_MAG_ZSCALE");
                activeUAS->requestParameter(0, "SENS_EXT_MAG_ROT");
            }
428 429 430 431 432

            if (text.startsWith("dpress ")) {
                activeUAS->requestParameter(0, "SENS_DPRES_OFF");
                activeUAS->requestParameter(0, "SENS_DPRES_ANA");
            }
433
        }
434 435
    }

Anton Babushkin's avatar
Anton Babushkin committed
436
    if (text.endsWith(" calibration: started")) {
Lorenz Meier's avatar
Lorenz Meier committed
437 438 439
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
    }

440 441 442 443 444 445 446 447
    // XXX color messages according to severity

    QPlainTextEdit *msgWidget = ui->textView;

    //turn off updates while we're appending content to avoid breaking the autoscroll behavior
    msgWidget->setUpdatesEnabled(false);
    QScrollBar *scroller = msgWidget->verticalScrollBar();

448
    msgWidget->appendHtml(QString("%4").arg(text));
449 450 451 452

    // Ensure text area scrolls correctly
    scroller->setValue(scroller->maximum());
    msgWidget->setUpdatesEnabled(true);
453
}
454

455 456
void QGCPX4SensorCalibration::gyroButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
457
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
458 459 460 461 462 463
    activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
    ui->progressBar->setValue(0);
}

void QGCPX4SensorCalibration::magButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
464
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
465 466 467 468 469 470
    activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
    ui->progressBar->setValue(0);
}

void QGCPX4SensorCalibration::accelButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
471
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
472 473
    activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0);
    ui->progressBar->setValue(0);
474 475
}

476 477 478 479 480 481 482
void QGCPX4SensorCalibration::diffPressureButtonClicked()
{
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
    activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0);
    ui->progressBar->setValue(0);
}

483 484 485 486 487 488
void QGCPX4SensorCalibration::contextMenuEvent(QContextMenuEvent* event)
{
    QMenu menu(this);
    menu.addAction(clearAction);
    menu.exec(event->globalPos());
}