QGCGoogleEarthView.cc 25.5 KB
Newer Older
1 2 3 4
#include <QApplication>
#include <QDir>
#include <QShowEvent>
#include <QSettings>
5
#include <QInputDialog>
6 7 8 9 10 11 12 13 14

#include <QDebug>
#include <QFile>
#include <QTextStream>
#include "UASManager.h"

#ifdef Q_OS_MAC
#include <QWebFrame>
#include <QWebPage>
15
#include <QWebElement>
16 17 18
#include "QGCWebPage.h"
#endif

19 20 21
#ifdef _MSC_VER
#include <QAxObject>
#include <QUuid>
22
#include <mshtml.h>
23 24
#include <comdef.h>
#include <qaxtypes.h>
25 26 27
#endif

#include "QGC.h"
28 29
#include "ui_QGCGoogleEarthView.h"
#include "QGCGoogleEarthView.h"
pixhawk's avatar
pixhawk committed
30
#include "UASWaypointManager.h"
31 32 33 34

#define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_")

QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
35 36 37 38 39 40 41 42 43 44
    QWidget(parent),
    updateTimer(new QTimer(this)),
    refreshRateMs(100),
    mav(NULL),
    followCamera(true),
    trailEnabled(true),
    webViewInitialized(false),
    jScriptInitialized(false),
    gEarthInitialized(false),
    currentViewMode(QGCGoogleEarthView::VIEW_MODE_SIDE),
45
#if (defined Q_OS_MAC)
46
    webViewMac(new QWebView(this)),
47 48
#endif
#ifdef _MSC_VER
49 50
    webViewWin(new QGCWebAxWidget(this)),
    documentWin(NULL),
51
#endif
52
    ui(new Ui::QGCGoogleEarthView)
53 54 55 56
{
#ifdef _MSC_VER
    // Create layout and attach webViewWin

57 58 59
//    QFile file("doc.html");
//    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
//        qDebug() << __FILE__ << __LINE__ << "Could not open log file";
60

61 62 63 64 65
//    QTextStream out(&file);
//    out << webViewWin->generateDocumentation();
//    out.flush();
//    file.flush();
//    file.close();
66 67 68 69 70 71 72 73 74 75 76 77 78


#else
#endif

    // Load settings
    QSettings settings;
    followCamera = settings.value(QGCGOOGLEEARTHVIEWSETTINGS + "follow", followCamera).toBool();
    trailEnabled = settings.value(QGCGOOGLEEARTHVIEWSETTINGS + "trail", trailEnabled).toBool();

    ui->setupUi(this);
#if (defined Q_OS_MAC)
    ui->webViewLayout->addWidget(webViewMac);
pixhawk's avatar
pixhawk committed
79
    //connect(webViewMac, SIGNAL(loadFinished(bool)), this, SLOT(initializeGoogleEarth(bool)));
80 81 82 83 84 85 86
#endif

#ifdef _MSC_VER
    ui->webViewLayout->addWidget(webViewWin);
#endif

    connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState()));
pixhawk's avatar
pixhawk committed
87
    connect(ui->resetButton, SIGNAL(clicked()), this, SLOT(reloadHTML()));
88
    connect(ui->changeViewButton, SIGNAL(clicked()), this, SLOT(toggleViewMode()));
89
    connect(ui->clearTrailsButton, SIGNAL(clicked()), this, SLOT(clearTrails()));
90 91
    connect(ui->atmosphereCheckBox, SIGNAL(clicked(bool)), this, SLOT(enableAtmosphere(bool)));
    connect(ui->daylightCheckBox, SIGNAL(clicked(bool)), this, SLOT(enableDaylight(bool)));
92 93

    connect(UASManager::instance(), SIGNAL(homePositionChanged(double,double,double)), this, SLOT(setHome(double,double,double)));
94 95 96 97 98 99 100 101
}

QGCGoogleEarthView::~QGCGoogleEarthView()
{
    QSettings settings;
    settings.setValue(QGCGOOGLEEARTHVIEWSETTINGS + "follow", followCamera);
    settings.setValue(QGCGOOGLEEARTHVIEWSETTINGS + "trail", trailEnabled);
    settings.sync();
102
#if (defined Q_OS_MAC)
103
    delete webViewMac;
104 105
#endif
#ifdef _MSC_VER
106
    delete webViewWin;
107
#endif
108 109 110
    delete ui;
}

111 112 113 114 115 116 117 118
/**
 * @param range in centimeters
 */
void QGCGoogleEarthView::setViewRangeScaledInt(int range)
{
    setViewRange(range/100.0f);
}

pixhawk's avatar
pixhawk committed
119 120 121 122 123 124 125 126 127
void QGCGoogleEarthView::reloadHTML()
{
    hide();
    webViewInitialized = false;
    jScriptInitialized = false;
    gEarthInitialized = false;
    show();
}

128 129 130 131 132
void QGCGoogleEarthView::enableEditMode(bool mode)
{
    javaScript(QString("setDraggingAllowed(%1);").arg(mode));
}

133 134 135 136 137 138 139 140 141 142
void QGCGoogleEarthView::enableDaylight(bool enable)
{
    javaScript(QString("enableDaylight(%1);").arg(enable));
}

void QGCGoogleEarthView::enableAtmosphere(bool enable)
{
    javaScript(QString("enableAtmosphere(%1);").arg(enable));
}

143 144 145 146 147 148 149 150
/**
 * @param range in meters (SI-units)
 */
void QGCGoogleEarthView::setViewRange(float range)
{
    javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5));
}

151 152 153 154 155
void QGCGoogleEarthView::setDistanceMode(int mode)
{
    javaScript(QString("setDistanceMode(%1);").arg(mode));
}

156 157
void QGCGoogleEarthView::toggleViewMode()
{
158
    switch (currentViewMode) {
159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175
    case VIEW_MODE_MAP:
        setViewMode(VIEW_MODE_SIDE);
        break;
    case VIEW_MODE_SIDE:
        setViewMode(VIEW_MODE_MAP);
        break;
    case VIEW_MODE_CHASE_LOCKED:
        setViewMode(VIEW_MODE_CHASE_FREE);
        break;
    case VIEW_MODE_CHASE_FREE:
        setViewMode(VIEW_MODE_CHASE_LOCKED);
        break;
    }
}

void QGCGoogleEarthView::setViewMode(QGCGoogleEarthView::VIEW_MODE mode)
{
176
    switch (mode) {
177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193
    case VIEW_MODE_MAP:
        ui->changeViewButton->setText("Free View");
        break;
    case VIEW_MODE_SIDE:
        ui->changeViewButton->setText("Map View");
        break;
    case VIEW_MODE_CHASE_LOCKED:
        ui->changeViewButton->setText("Free Chase");
        break;
    case VIEW_MODE_CHASE_FREE:
        ui->changeViewButton->setText("Fixed Chase");
        break;
    }
    currentViewMode = mode;
    javaScript(QString("setViewMode(%1);").arg(mode));
}

194 195
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
196 197 198 199 200 201 202 203 204 205 206 207
    // uasid, type, color (in #rrbbgg format)
    QString uasColor = uas->getColor().name().remove(0, 1);
    // Convert to bbggrr format
    QString rChannel = uasColor.mid(0, 2);
    uasColor.remove(0, 2);
    uasColor.prepend(rChannel);
    // Set alpha value to 0x66, append JavaScript quotes ('')
    uasColor.prepend("'66").append("'");
    javaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg(uasColor));

    if (trailEnabled) javaScript(QString("showTrail(%1);").arg(uas->getUASID()));

208 209
    // Automatically receive further position updates
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
pixhawk's avatar
pixhawk committed
210 211
    // Receive waypoint updates
    // Connect the waypoint manager / data storage to the UI
212 213 214
    connect(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
    connect(uas->getWaypointManager(), SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
    //connect(this, SIGNAL(waypointCreated(Waypoint*)), uas->getWaypointManager(), SLOT(addWaypointEditable(Waypoint*)));
pixhawk's avatar
pixhawk committed
215
    // TODO Update waypoint list on UI changes here
216 217 218 219
}

void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
{
220 221
    if (uas)
    {
222
        mav = uas;
223
        javaScript(QString("setCurrAircraft(%1);").arg(uas->getUASID()));
224
        updateWaypointList(uas->getUASID());
225 226 227
    }
}

pixhawk's avatar
pixhawk committed
228 229 230 231 232 233 234
/**
 * This function is called if a a single waypoint is updated and
 * also if the whole list changes.
 */
void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
{
    // Only accept waypoints in global coordinate frame
235
    if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
236
    {
pixhawk's avatar
pixhawk committed
237 238 239
        // We're good, this is a global waypoint

        // Get the index of this waypoint
lm's avatar
lm committed
240
        // note the call to getGlobalFrameAndNavTypeIndexOf()
pixhawk's avatar
pixhawk committed
241
        // as we're only handling global waypoints
lm's avatar
lm committed
242
        int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameAndNavTypeIndexOf(wp);
pixhawk's avatar
pixhawk committed
243
        // If not found, return (this should never happen, but helps safety)
244 245
        if (wpindex == -1)
        {
pixhawk's avatar
pixhawk committed
246
            return;
247 248 249
        }
        else
        {
250
            javaScript(QString("updateWaypoint(%1,%2,%3,%4,%5,%6);").arg(uas).arg(wpindex).arg(wp->getLatitude(), 0, 'f', 22).arg(wp->getLongitude(), 0, 'f', 22).arg(wp->getAltitude(), 0, 'f', 22).arg(wp->getAction()));
251
            //qDebug() << QString("updateWaypoint(%1,%2,%3,%4,%5,%6);").arg(uas).arg(wpindex).arg(wp->getLatitude(), 0, 'f', 18).arg(wp->getLongitude(), 0, 'f', 18).arg(wp->getAltitude(), 0, 'f', 18).arg(wp->getAction());
pixhawk's avatar
pixhawk committed
252 253 254 255 256 257 258 259 260 261 262 263 264
        }
    }
}

/**
 * Update the whole list of waypoints. This is e.g. necessary if the list order changed.
 * The UAS manager will emit the appropriate signal whenever updating the list
 * is necessary.
 */
void QGCGoogleEarthView::updateWaypointList(int uas)
{
    // Get already existing waypoints
    UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
265 266
    if (uasInstance)
    {
pixhawk's avatar
pixhawk committed
267
        // Get all waypoints, including non-global waypoints
lm's avatar
lm committed
268
        QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
pixhawk's avatar
pixhawk committed
269 270 271 272

        // Trim internal list to number of global waypoints in the waypoint manager list
        javaScript(QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count()));

lm's avatar
lm committed
273 274
        qDebug() << QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count());

pixhawk's avatar
pixhawk committed
275
        // Load all existing waypoints into map view
276 277
        foreach (Waypoint* wp, wpList)
        {
pixhawk's avatar
pixhawk committed
278 279 280 281 282
            updateWaypoint(uas, wp);
        }
    }
}

283
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
284 285
{
    Q_UNUSED(usec);
286
    javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 22).arg(lon, 0, 'f', 22).arg(alt, 0, 'f', 22));
287 288
}

289 290 291
void QGCGoogleEarthView::clearTrails()
{
    QList<UASInterface*> mavs = UASManager::instance()->getUASList();
292 293
    foreach (UASInterface* currMav, mavs)
    {
294 295 296 297
        javaScript(QString("clearTrail(%1);").arg(currMav->getUASID()));
    }
}

298 299
void QGCGoogleEarthView::showTrail(bool state)
{
300
    // Check if the current trail has to be hidden
301 302
    if (trailEnabled && !state)
    {
303
        QList<UASInterface*> mavs = UASManager::instance()->getUASList();
304 305
        foreach (UASInterface* currMav, mavs)
        {
306
            javaScript(QString("hideTrail(%1);").arg(currMav->getUASID()));
307 308 309 310
        }
    }

    // Check if the current trail has to be shown
311 312
    if (!trailEnabled && state)
    {
313
        QList<UASInterface*> mavs = UASManager::instance()->getUASList();
314 315
        foreach (UASInterface* currMav, mavs)
        {
316 317 318 319
            javaScript(QString("showTrail(%1);").arg(currMav->getUASID()));
        }
    }
    trailEnabled = state;
320 321 322 323 324
    ui->trailCheckbox->setChecked(state);
}

void QGCGoogleEarthView::showWaypoints(bool state)
{
pixhawk's avatar
pixhawk committed
325
    waypointsEnabled = state;
326 327 328 329 330
}

void QGCGoogleEarthView::follow(bool follow)
{
    ui->followAirplaneCheckbox->setChecked(follow);
331 332 333 334
    if (follow != followCamera)
    {
        if (follow)
        {
335
            setViewMode(VIEW_MODE_CHASE_LOCKED);
336 337 338
        }
        else
        {
339 340 341
            setViewMode(VIEW_MODE_SIDE);
        }
    }
342
    followCamera = follow;
343
    javaScript(QString("setFollowEnabled(%1)").arg(follow));
344 345 346 347 348 349 350 351
}

void QGCGoogleEarthView::goHome()
{
    // Disable follow and update
    follow(false);
    updateState();
    // Go to home location
352
    javaScript("goHome();");
353 354 355 356
}

void QGCGoogleEarthView::setHome(double lat, double lon, double alt)
{
357
    qDebug() << "SETTING GCS HOME IN GOOGLE MAPS" << lat << lon << alt;
358
    javaScript(QString("setGCSHome(%1,%2,%3);").arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
359 360
}

361 362 363 364 365 366 367 368 369 370 371 372 373 374
void QGCGoogleEarthView::setHome()
{
    javaScript(QString("enableSetHomeMode();"));
}

void QGCGoogleEarthView::moveToPosition()
{
    bool ok;
    javaScript("sampleCurrentPosition();");
    double latitude = documentElement("currentCameraLatitude").toDouble();
    double longitude = documentElement("currentCameraLongitude").toDouble();
    QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
                                         tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
                                         QString("%1,%2").arg(latitude).arg(longitude), &ok);
375
    if (ok && !text.isEmpty()) {
376
        QStringList split = text.split(",");
377
        if (split.length() == 2) {
378 379 380 381 382 383
            bool convert;
            double latitude = split.first().toDouble(&convert);
            ok &= convert;
            double longitude = split.last().toDouble(&convert);
            ok &= convert;

384
            if (ok) {
385 386 387 388 389 390
                javaScript(QString("setLookAtLatLon(%1,%2);").arg(latitude, 0, 'f', 15).arg(longitude, 0, 'f', 15));
            }
        }
    }
}

391 392
void QGCGoogleEarthView::hideEvent(QHideEvent* event)
{
393
    updateTimer->stop();
LM's avatar
LM committed
394 395
    QWidget::hideEvent(event);
    emit visibilityChanged(false);
396 397
}

398 399 400 401
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
LM's avatar
LM committed
402
    QWidget::showEvent(event);
403
    // Enable widget, initialize on first run
404

LM's avatar
LM committed
405 406
    if (!webViewInitialized)
    {
407
#if (defined Q_OS_MAC)
408 409 410
        webViewMac->setPage(new QGCWebPage(webViewMac));
        webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
        webViewMac->load(QUrl(QCoreApplication::applicationDirPath()+"/earth.html"));
411 412 413
#endif

#ifdef _MSC_VER
414 415
        //webViewWin->dynamicCall("GoHome()");
        webViewWin->dynamicCall("Navigate(const QString&)", QApplication::applicationDirPath() + "/earth.html");
416 417
#endif

418 419 420
        webViewInitialized = true;
        // Reloading the webpage, this resets Google Earth
        gEarthInitialized = false;
421

422
        QTimer::singleShot(3000, this, SLOT(initializeGoogleEarth()));
LM's avatar
LM committed
423 424 425
    }
    else
    {
426 427
        updateTimer->start(refreshRateMs);
    }
LM's avatar
LM committed
428
    emit visibilityChanged(true);
429 430
}

431 432
void QGCGoogleEarthView::printWinException(int no, QString str1, QString str2, QString str3)
{
433
    qDebug() << no << str1 << str2 << str3;
434 435 436 437 438
}

QVariant QGCGoogleEarthView::javaScript(QString javaScript)
{
#ifdef Q_OS_MAC
439
    if (!jScriptInitialized) {
440
        return QVariant(false);
441
    } else {
442 443
        return webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript);
    }
444 445
#endif
#ifdef _MSC_VER
446
    if(!jScriptInitialized) {
447 448
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
        return QVariant(false);
449
    } else {
450 451 452
        QVariantList params;
        params.append(javaScript);
        params.append("JScript");
453 454
        QVariant result = jScriptWin->dynamicCall("execScript(QString, QString)", params);
        return result;
455
    }
456 457 458
#endif
}

459 460 461 462 463 464 465 466
QVariant QGCGoogleEarthView::documentElement(QString name)
{
#ifdef Q_OS_MAC
    QString javaScript("getGlobal(%1)");
    QVariant result = webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript.arg(name));
    return result;
#endif
#ifdef _MSC_VER
467
    if(!jScriptInitialized) {
468
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
469 470
    } else {
        if (documentWin) {
471 472 473 474 475 476 477 478 479 480 481 482
            QString resultString;

            // Get HTMLElement object
            QVariantList params;
            IHTMLDocument3* doc;
            documentWin->queryInterface( IID_IHTMLDocument3, (void**)&doc);
            params.append(name);
            IHTMLElement* element = NULL;
            // Append alias
            name.prepend("JScript_");
            HRESULT res = doc->getElementById(QStringToBSTR(name), &element);
            //BSTR elemString;
lm's avatar
lm committed
483
            if (SUCCEEDED(res) && element) {
484 485 486 487
                //element->get_innerHTML(&elemString);
                VARIANT var;
                var.vt = VT_BSTR;
                HRESULT res = element->getAttribute(L"value", 0, &var);
488
                if (SUCCEEDED(res) && (var.vt != VT_NULL)) {
489 490 491
                    QByteArray typeName;
                    QVariant qtValue = VARIANTToQVariant(var,typeName);
                    return qtValue;
492
                } else {
493 494
                    qDebug() << __FILE__ << __LINE__ << "JAVASCRIPT ATTRIBUTE" << name << "NOT FOUND";
                }
495
            } else {
496 497 498
                qDebug() << __FILE__ << __LINE__ << "DID NOT GET HTML ELEMENT" << name;
            }
        }
499
    }
500
    return QVariant(0);
501 502 503
#endif
}

504 505
void QGCGoogleEarthView::initializeGoogleEarth()
{
506
    if (!jScriptInitialized) {
507 508
#ifdef Q_OS_MAC
        jScriptInitialized = true;
509
#endif
510 511
#ifdef _MSC_VER
        QAxObject* doc = webViewWin->querySubObject("Document()");
512
        //IDispatch* Disp;
513
        IDispatch* winDoc = NULL;
514
        IHTMLDocument2* document = NULL;
515 516 517 518

        //332C4425-26CB-11D0-B483-00C04FD90119 IHTMLDocument2
        //25336920-03F9-11CF-8FD0-00AA00686F13 HTMLDocument
        doc->queryInterface(QUuid("{332C4425-26CB-11D0-B483-00C04FD90119}"), (void**)(&winDoc));
519
        if (winDoc) {
520
            document = NULL;
521 522 523
            winDoc->QueryInterface( IID_IHTMLDocument2, (void**)&document );
            IHTMLWindow2 *window = NULL;
            document->get_parentWindow( &window );
524
            documentWin = new QAxObject(document, webViewWin);
525 526 527
            jScriptWin = new QAxObject(window, webViewWin);
            connect(jScriptWin, SIGNAL(exception(int,QString,QString,QString)), this, SLOT(printWinException(int,QString,QString,QString)));
            jScriptInitialized = true;
528
        } else {
529 530
            qDebug() << "COULD NOT GET DOCUMENT OBJECT! Aborting";
        }
531
#endif
532
        QTimer::singleShot(1500, this, SLOT(initializeGoogleEarth()));
533 534
        return;
    }
535

536 537
    if (!gEarthInitialized) {
        if (!documentElement("initialized").toBool()) {
538
            QTimer::singleShot(300, this, SLOT(initializeGoogleEarth()));
539
            qDebug() << "NOT INITIALIZED, WAITING";
540
        } else {
541 542
            gEarthInitialized = true;

543
            // Set home location
544
            setHome(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
545 546 547

            // Add all MAVs
            QList<UASInterface*> mavs = UASManager::instance()->getUASList();
548
            foreach (UASInterface* currMav, mavs) {
549
                addUAS(currMav);
550 551
            }

552 553 554
            // Set current UAS
            setActiveUAS(UASManager::instance()->getActiveUAS());

555
            // Add any further MAV automatically
556 557
            connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
            connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
558 559 560 561 562

            // Connect UI signals/slots

            // Follow checkbox
            ui->followAirplaneCheckbox->setChecked(followCamera);
563
            connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool)), Qt::UniqueConnection);
564 565 566

            // Trail checkbox
            ui->trailCheckbox->setChecked(trailEnabled);
567
            connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool)), Qt::UniqueConnection);
568 569 570

            // Go home
            connect(ui->goHomeButton, SIGNAL(clicked()), this, SLOT(goHome()));
571 572 573 574 575 576 577 578 579
            // Set home
            connect(ui->setHomeButton, SIGNAL(clicked()), this, SLOT(setHome()));

            // Visibility of set home button
            connect(ui->editButton, SIGNAL(clicked(bool)), ui->setHomeButton, SLOT(setVisible(bool)));
            ui->setHomeButton->setVisible(ui->editButton->isChecked());

            // To Lat/Lon button
            connect(ui->toLatLonButton, SIGNAL(clicked()), this, SLOT(moveToPosition()));
580 581

            // Cam distance slider
582
            connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int)), Qt::UniqueConnection);
583
            setViewRangeScaledInt(ui->camDistanceSlider->value());
584

585 586 587 588 589
            // Distance combo box
            connect(ui->camDistanceComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setDistanceMode(int)), Qt::UniqueConnection);
            // Edit mode button
            connect(ui->editButton, SIGNAL(clicked(bool)), this, SLOT(enableEditMode(bool)), Qt::UniqueConnection);

590 591 592
            // Update waypoint list
            if (mav) updateWaypointList(mav->getUASID());

593 594 595
            // Start update timer
            updateTimer->start(refreshRateMs);

596 597
            // Set current view mode
            setViewMode(currentViewMode);
598 599
            setDistanceMode(ui->camDistanceComboBox->currentIndex());
            enableEditMode(ui->editButton->isChecked());
600 601
            enableAtmosphere(ui->atmosphereCheckBox->isChecked());
            enableDaylight(ui->daylightCheckBox->isChecked());
pixhawk's avatar
pixhawk committed
602
            follow(this->followCamera);
603 604 605

            // Move to home location
            goHome();
606 607 608 609 610 611
        }
    }
}

void QGCGoogleEarthView::updateState()
{
612 613 614
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
615 616
    if (gEarthInitialized)
    {
617 618 619 620 621 622 623 624 625 626 627
        int uasId = 0;
        double lat = 47.3769;
        double lon = 8.549444;
        double alt = 470.0;

        float roll = 0.0f;
        float pitch = 0.0f;
        float yaw = 0.0f;

        // Update all MAVs
        QList<UASInterface*> mavs = UASManager::instance()->getUASList();
628 629
        foreach (UASInterface* currMav, mavs)
        {
630 631
            // Only update if known
            if (!currMav->globalPositionKnown()) continue;
632 633 634 635 636 637 638
            uasId = currMav->getUASID();
            lat = currMav->getLatitude();
            lon = currMav->getLongitude();
            alt = currMav->getAltitude();
            roll = currMav->getRoll();
            pitch = currMav->getPitch();
            yaw = currMav->getYaw();
639

640 641
            //qDebug() << "SETTING POSITION FOR" << uasId << lat << lon << alt << roll << pitch << yaw;

642
            javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
643
                       .arg(uasId)
644 645 646
                       .arg(lat, 0, 'f', 22)
                       .arg(lon, 0, 'f', 22)
                       .arg(alt, 0, 'f', 22)
647 648 649
                       .arg(roll, 0, 'f', 9)
                       .arg(pitch, 0, 'f', 9)
                       .arg(yaw, 0, 'f', 9));
650
        }
651 652 653 654 655 656 657 658


        // Read out new waypoint positions and waypoint create events
        // this is polling (bad) but forced because of the crappy
        // Microsoft API available in Qt - improvements wanted

        // First check if a new WP should be created
        bool newWaypointPending = documentElement("newWaypointPending").toBool();
659 660
        if (newWaypointPending)
        {
661 662 663 664 665 666 667 668
            bool coordsOk = true;
            bool ok;
            double latitude = documentElement("newWaypointLatitude").toDouble(&ok);
            coordsOk &= ok;
            double longitude = documentElement("newWaypointLongitude").toDouble(&ok);
            coordsOk &= ok;
            double altitude = documentElement("newWaypointAltitude").toDouble(&ok);
            coordsOk &= ok;
669 670
            if (coordsOk)
            {
671
                // Add new waypoint
672 673
                if (mav)
                {
674
                    Waypoint* wp = mav->getWaypointManager()->createWaypoint();
675
                    wp->setFrame(MAV_FRAME_GLOBAL);
676 677 678 679
                    wp->setAction(MAV_CMD_NAV_WAYPOINT);
                    wp->setLatitude(latitude);
                    wp->setLongitude(longitude);
                    wp->setAltitude(altitude);
680
                    wp->setAcceptanceRadius(10.0); // 10 m
681 682 683 684 685 686 687 688
                }
            }
            javaScript("setNewWaypointPending(false);");
        }

        // Check if a waypoint should be moved
        bool dragWaypointPending = documentElement("dragWaypointPending").toBool();

689 690
        if (dragWaypointPending)
        {
691 692 693 694 695 696 697 698
            bool coordsOk = true;
            bool ok;
            double latitude = documentElement("dragWaypointLatitude").toDouble(&ok);
            coordsOk &= ok;
            double longitude = documentElement("dragWaypointLongitude").toDouble(&ok);
            coordsOk &= ok;
            double altitude = documentElement("dragWaypointAltitude").toDouble(&ok);
            coordsOk &= ok;
699 700

            // UPDATE WAYPOINTS, HOME LOCATION AND OTHER LOCATIONS
701 702
            if (coordsOk)
            {
703
                QString idText = documentElement("dragWaypointIndex").toString();
704 705
                if (idText == "HOME")
                {
706 707 708
                    qDebug() << "HOME UPDATED!";
                    UASManager::instance()->setHomePosition(latitude, longitude, altitude);
                    ui->setHomeButton->setChecked(false);
709 710 711
                }
                else
                {
712
                    // Update waypoint or symbol
713 714
                    if (mav)
                    {
lm's avatar
lm committed
715
                        QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
716 717 718 719

                        bool ok;
                        int index = idText.toInt(&ok);

720 721
                        if (ok && index >= 0 && index < wps.count())
                        {
722 723 724 725
                            Waypoint* wp = wps.at(index);
                            wp->setLatitude(latitude);
                            wp->setLongitude(longitude);
                            wp->setAltitude(altitude);
726
                            mav->getWaypointManager()->notifyOfChangeEditable(wp);
727
                        }
728 729
                    }
                }
730 731 732
            }
            else
            {
733 734 735 736 737 738
                // If coords were not ok, move the view in google earth back
                // to last acceptable location
                updateWaypointList(mav->getUASID());
            }
            javaScript("setDragWaypointPending(false);");
        }
739 740 741 742 743 744 745 746 747 748 749 750 751 752 753
    }
}


void QGCGoogleEarthView::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
    switch (e->type()) {
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}