QGCPX4SensorCalibration.cc 16.9 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

QGCPX4SensorCalibration::QGCPX4SensorCalibration(QWidget *parent) :
    QWidget(parent),
    activeUAS(NULL),
    clearAction(new QAction(tr("Clear Text"), this)),
12 13 14
    accelStarted(false),
    gyroStarted(false),
    magStarted(false),
15 16
    ui(new Ui::QGCPX4SensorCalibration)
{
17 18 19 20 21 22 23
    accelAxes << "x+";
    accelAxes << "x-";
    accelAxes << "y+";
    accelAxes << "y-";
    accelAxes << "z+";
    accelAxes << "z-";

Lorenz Meier's avatar
Lorenz Meier committed
24

25 26 27
    ui->setupUi(this);
    connect(clearAction, SIGNAL(triggered()), ui->textView, SLOT(clear()));

28 29 30 31 32 33 34 35
    connect(ui->gyroButton, SIGNAL(clicked()), this, SLOT(gyroButtonClicked()));
    connect(ui->magButton, SIGNAL(clicked()), this, SLOT(magButtonClicked()));
    connect(ui->accelButton, SIGNAL(clicked()), this, SLOT(accelButtonClicked()));

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

36 37 38
    ui->autopilotComboBox->setEnabled(false);
    ui->magComboBox->setEnabled(false);

Lorenz Meier's avatar
Lorenz Meier committed
39
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 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
    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);

    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);
97 98 99 100 101 102 103

    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*)));
104
    ui->progressBar->setValue(0);
105 106 107 108 109

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

    // XXX ask for params (if not loaded)
110 111 112 113 114 115 116
}

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

117 118 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 172 173 174 175 176 177 178 179 180 181 182 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
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);
        }
    }
}

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

217 218 219 220 221 222 223
void QGCPX4SensorCalibration::setInstructionImage(const QString &path)
{
    instructionIcon.load(path);

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

224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270
    ui->iconLabel->setPixmap(instructionIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));
}

void QGCPX4SensorCalibration::setAutopilotImage(int index)
{
    setAutopilotImage(QString(":/files/images/px4/calibration/pixhawk_%1.png").arg(index));
}

void QGCPX4SensorCalibration::setGpsImage(int index)
{
    setGpsImage(QString(":/files/images/px4/calibration/gps_%1.png").arg(index));
}

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)
{
    autopilotIcon.load(path);

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

    ui->autopilotLabel->setPixmap(autopilotIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));
}

void QGCPX4SensorCalibration::setGpsImage(const QString &path)
{
    gpsIcon.load(path);

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

    ui->gpsLabel->setPixmap(gpsIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation));
271 272 273 274 275 276 277
}

void QGCPX4SensorCalibration::resizeEvent(QResizeEvent* event)
{

    int w = ui->iconLabel->width();
    int h = ui->iconLabel->height();
278 279 280 281 282
    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));
283

284 285 286
    int wg = ui->gpsLabel->width();
    int hg = ui->gpsLabel->height();
    ui->gpsLabel->setPixmap(gpsIcon.scaled(wg, hg, Qt::KeepAspectRatio, Qt::SmoothTransformation));
287 288 289 290 291 292 293 294 295 296

    QWidget::resizeEvent(event);
}

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

    if (activeUAS) {
297 298
        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)));
299 300 301
        ui->textView->clear();
    }

302 303 304 305
    ui->gyroButton->setEnabled(true);
    ui->magButton->setEnabled(true);
    ui->accelButton->setEnabled(true);

306
    connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(handleTextMessage(int,int,int,QString)));
307
    connect(uas, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant)));
308 309 310 311 312
    activeUAS = uas;
}

void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int severity, QString text)
{
Lorenz Meier's avatar
Lorenz Meier committed
313 314 315 316
    Q_UNUSED(uasid);
    Q_UNUSED(compId);
    Q_UNUSED(severity);

317 318 319 320 321 322 323 324 325 326 327 328 329 330 331
    if (text.startsWith("[cmd]") ||
        text.startsWith("[mavlink pm]"))
        return;

    if (text.contains("progress")) {
        qDebug() << "PROGRESS:" << text;
        QString percent = text.split("<").last().split(">").first();
        qDebug() << "PERCENT CANDIDATE" << percent;
        bool ok;
        int p = percent.toInt(&ok);
        if (ok)
            ui->progressBar->setValue(p);
        return;
    }

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

334 335 336 337

    if (text.contains("accel")) {
        qDebug() << "ACCEL" << text;

Lorenz Meier's avatar
Lorenz Meier committed
338 339
        if (text.startsWith("accel measurement started: ")) {
            QString axis = text.split("measurement started: ").last().left(2);
340
            qDebug() << "AXIS" << axis << "STR" << text;
Lorenz Meier's avatar
Lorenz Meier committed
341
            setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis));
342 343 344 345

        }
    }

Lorenz Meier's avatar
Lorenz Meier committed
346 347 348 349 350 351 352 353 354 355 356
    if (text.startsWith("directions left")) {
        for (int i = 0; i < 6; i++)
        {
            if (!text.contains(accelAxes[i])) {
                qDebug() << "FINISHED" << accelAxes[i];
                accelDone[i] = true;
            }
        }
    }

    if (text.startsWith("result for")) {
357

Lorenz Meier's avatar
Lorenz Meier committed
358
        QString axis = text.split("result for ").last().left(2);
359 360 361 362 363

        qDebug() << "ACCELDONE AXIS" << axis << "STR" << text;

        for (int i = 0; i < 6; i++)
        {
Lorenz Meier's avatar
Lorenz Meier committed
364
            if (axis == accelAxes[i])
365 366 367
                accelDone[i] = true;

            if (!accelDone[i]) {
Lorenz Meier's avatar
Lorenz Meier committed
368
                qDebug() << "NEW AXIS: " << accelAxes[i];
Lorenz Meier's avatar
Lorenz Meier committed
369
                setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(accelAxes[i]));
Lorenz Meier's avatar
Lorenz Meier committed
370 371
                ui->instructionLabel->setText(tr("Axis %1 completed. Please rotate like shown here.").arg(axis));
                break;
372 373 374 375 376
            }
        }
    }

    if (text.contains("please rotate in a figure 8")) {
Lorenz Meier's avatar
Lorenz Meier committed
377
        setInstructionImage(":/files/images/px4/calibration/mag_calibration_figure8.png");
378 379 380 381 382
    }

    if (text.contains("accel calibration done")) {
        accelStarted = false;
        // XXX use a confirmation image or something
Lorenz Meier's avatar
Lorenz Meier committed
383
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
384 385
        if (activeUAS)
            activeUAS->requestParameter(0, "SENS_ACC_XOFF");
386 387 388 389 390
    }

    if (text.contains("gyro calibration done")) {
        gyroStarted = false;
        // XXX use a confirmation image or something
Lorenz Meier's avatar
Lorenz Meier committed
391
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
392 393
        if (activeUAS)
            activeUAS->requestParameter(0, "SENS_GYRO_XOFF");
394 395
    }

Lorenz Meier's avatar
Lorenz Meier committed
396 397
    if (text.contains("mag calibration done")
            || text.contains("magnetometer calibration completed")) {
398 399
        magStarted = false;
        // XXX use a confirmation image or something
Lorenz Meier's avatar
Lorenz Meier committed
400
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
401 402
        if (activeUAS)
            activeUAS->requestParameter(0, "SENS_MAG_XOFF");
403 404
    }

Lorenz Meier's avatar
Lorenz Meier committed
405 406 407 408 409 410 411 412 413 414 415 416 417 418
    if (text.contains("accel calibration started")) {
        accelStarted = true;
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
    }

    if (text.contains("gyro calibration started")) {
        gyroStarted = true;
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
    }

    if (text.contains("mag calibration started")) {
        magStarted = false;
        setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
    }
419 420


421 422 423 424 425 426 427 428
    // 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();

429
    msgWidget->appendHtml(QString("%4").arg(text));
430 431 432 433

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

436 437
void QGCPX4SensorCalibration::gyroButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
438
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
439 440
    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);
Lorenz Meier's avatar
Lorenz Meier committed
441
    ui->instructionLabel->setText(tr("Please do not move the system at all."));
442 443 444 445
}

void QGCPX4SensorCalibration::magButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
446
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
447 448
    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);
Lorenz Meier's avatar
Lorenz Meier committed
449
    ui->instructionLabel->setText(tr("Please put the system in a rest position."));
450 451 452 453
}

void QGCPX4SensorCalibration::accelButtonClicked()
{
Lorenz Meier's avatar
Lorenz Meier committed
454
    setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
455 456 457 458 459 460 461 462 463 464
    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);
    accelStarted = true;
    accelDone[0] = false;
    accelDone[1] = false;
    accelDone[2] = false;
    accelDone[3] = false;
    accelDone[4] = false;
    accelDone[5] = false;

Lorenz Meier's avatar
Lorenz Meier committed
465
    ui->instructionLabel->setText(tr("Please hold the system very still in the shown orientations."));
466 467 468 469 470 471 472 473
}

void QGCPX4SensorCalibration::contextMenuEvent(QContextMenuEvent* event)
{
    QMenu menu(this);
    menu.addAction(clearAction);
    menu.exec(event->globalPos());
}