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

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

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

18 19 20
#ifdef _MSC_VER
#include <QAxObject>
#include <QUuid>
21
#include <mshtml.h>
22 23 24
#endif

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

#define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_")

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

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

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


#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
76
    //connect(webViewMac, SIGNAL(loadFinished(bool)), this, SLOT(initializeGoogleEarth(bool)));
77 78 79 80 81 82 83
#endif

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

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

QGCGoogleEarthView::~QGCGoogleEarthView()
{
    QSettings settings;
    settings.setValue(QGCGOOGLEEARTHVIEWSETTINGS + "follow", followCamera);
    settings.setValue(QGCGOOGLEEARTHVIEWSETTINGS + "trail", trailEnabled);
    settings.sync();
97 98 99 100 101 102
#if (defined Q_OS_MAC)
        delete webViewMac;
#endif
#ifdef _MSC_VER
        delete webViewWin;
#endif
103 104 105
    delete ui;
}

106 107 108 109 110 111 112 113
/**
 * @param range in centimeters
 */
void QGCGoogleEarthView::setViewRangeScaledInt(int range)
{
    setViewRange(range/100.0f);
}

pixhawk's avatar
pixhawk committed
114 115 116 117 118 119 120 121 122
void QGCGoogleEarthView::reloadHTML()
{
    hide();
    webViewInitialized = false;
    jScriptInitialized = false;
    gEarthInitialized = false;
    show();
}

123 124 125 126 127
void QGCGoogleEarthView::enableEditMode(bool mode)
{
    javaScript(QString("setDraggingAllowed(%1);").arg(mode));
}

128 129 130 131 132 133 134 135 136 137
void QGCGoogleEarthView::enableDaylight(bool enable)
{
    javaScript(QString("enableDaylight(%1);").arg(enable));
}

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

138 139 140 141 142 143 144 145
/**
 * @param range in meters (SI-units)
 */
void QGCGoogleEarthView::setViewRange(float range)
{
    javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5));
}

146 147 148 149 150
void QGCGoogleEarthView::setDistanceMode(int mode)
{
    javaScript(QString("setDistanceMode(%1);").arg(mode));
}

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
void QGCGoogleEarthView::toggleViewMode()
{
    switch (currentViewMode)
    {
    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)
{
    switch (mode)
    {
    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));
}

191 192
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
193 194 195 196 197 198 199 200 201 202 203 204
    // 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()));

205 206
    // 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
207 208 209 210 211 212
    // Receive waypoint updates
    // Connect the waypoint manager / data storage to the UI
    connect(uas->getWaypointManager(), SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int)));
    connect(uas->getWaypointManager(), SIGNAL(waypointChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
    //connect(this, SIGNAL(waypointCreated(Waypoint*)), uas->getWaypointManager(), SLOT(addWaypoint(Waypoint*)));
    // TODO Update waypoint list on UI changes here
213 214 215 216 217 218 219
}

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

pixhawk's avatar
pixhawk committed
225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246
/**
 * 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
    if (wp->getFrame() == MAV_FRAME_GLOBAL)
    {
        // We're good, this is a global waypoint

        // Get the index of this waypoint
        // note the call to getGlobalFrameIndexOf()
        // as we're only handling global waypoints
        int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameIndexOf(wp);
        // If not found, return (this should never happen, but helps safety)
        if (wpindex == -1)
        {
            return;
        }
        else
        {
lm's avatar
lm committed
247
            javaScript(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()));
248
            //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
249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269
        }
    }
}

/**
 * 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);
    if (uasInstance)
    {
        // Get all waypoints, including non-global waypoints
        QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameWaypointList();

        // 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
270 271
        qDebug() << QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count());

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

280
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
281 282
{
    Q_UNUSED(usec);
lm's avatar
lm committed
283
    javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 18).arg(lon, 0, 'f', 18).arg(alt, 0, 'f', 15));
284

lm's avatar
lm committed
285
    //qDebug() << QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15);
286 287
}

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

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

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

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

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

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

void QGCGoogleEarthView::setHome(double lat, double lon, double alt)
{
356
    javaScript(QString("setGCSHome(%1,%2,%3);").arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
357 358
}

359 360
void QGCGoogleEarthView::hideEvent(QHideEvent* event)
{
361 362
    Q_UNUSED(event);
    updateTimer->stop();
363 364
}

365 366 367 368
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
369
    Q_UNUSED(event)
370
        // Enable widget, initialize on first run
371

372
        if (!webViewInitialized)
373
        {
374
#if (defined Q_OS_MAC)
375 376
            webViewMac->setPage(new QGCWebPage(webViewMac));
            webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
pixhawk's avatar
pixhawk committed
377
            webViewMac->load(QUrl(QCoreApplication::applicationDirPath()+"/earth.html"));
378 379 380
#endif

#ifdef _MSC_VER
381 382
            //webViewWin->dynamicCall("GoHome()");
            webViewWin->dynamicCall("Navigate(const QString&)", QApplication::applicationDirPath() + "/earth.html");
383 384
#endif

385 386 387
            webViewInitialized = true;
            // Reloading the webpage, this resets Google Earth
            gEarthInitialized = false;
388

389
            QTimer::singleShot(10000, this, SLOT(initializeGoogleEarth()));
390 391 392
        }
        else
        {
393 394
            updateTimer->start(refreshRateMs);
        }
395 396
}

397 398
void QGCGoogleEarthView::printWinException(int no, QString str1, QString str2, QString str3)
{
399
    qDebug() << no << str1 << str2 << str3;
400 401 402 403 404
}

QVariant QGCGoogleEarthView::javaScript(QString javaScript)
{
#ifdef Q_OS_MAC
405 406 407 408 409 410 411 412
    if (!gEarthInitialized)
    {
        return QVariant(false);
    }
    else
    {
        return webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript);
    }
413 414
#endif
#ifdef _MSC_VER
415 416 417 418 419 420 421 422 423 424
    if(!jScriptInitialized)
    {
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
        return QVariant(false);
    }
    else
    {
        QVariantList params;
        params.append(javaScript);
        params.append("JScript");
425 426
        QVariant result = jScriptWin->dynamicCall("execScript(QString, QString)", params);
        return result;
427
    }
428 429 430
#endif
}

431 432 433 434 435 436 437 438 439 440 441 442 443 444 445
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
    if(!jScriptInitialized)
    {
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
        return QVariant(false);
    }
    else
    {
446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461
        QVariantList params;
        QString javaScript("getGlobal(%1)");
        params.append(javaScript.arg(name));
        params.append("JScript");
        QVariant result = jScriptWin->dynamicCall("execScript(QString, QString)", params);
        qDebug() << "JScript result: " << result << result.toDouble();
//		if (documentWin)
//		{
//			// Get HTMLElement object
//			QVariantList params;
//			params.append(name);
//			//QAxObject* elementWin = documentWin->dynamicCall("getElementById(QString)", params);
//			QVariant result =documentWin->dynamicCall("toString()");
//			qDebug() << "GOT RESULT" << result;
//			return QVariant(0);//QVariant(result);
//		}
462 463 464 465
    }
#endif
}

466 467
void QGCGoogleEarthView::initializeGoogleEarth()
{
468 469 470 471
    if (!jScriptInitialized)
    {
#ifdef Q_OS_MAC
        jScriptInitialized = true;
472
#endif
473 474
#ifdef _MSC_VER
        QAxObject* doc = webViewWin->querySubObject("Document()");
475
        //IDispatch* Disp;
476
        IDispatch* winDoc = NULL;
477
		IHTMLDocument2* document = NULL;
478 479 480 481 482 483 484 485 486 487

        //332C4425-26CB-11D0-B483-00C04FD90119 IHTMLDocument2
        //25336920-03F9-11CF-8FD0-00AA00686F13 HTMLDocument
        doc->queryInterface(QUuid("{332C4425-26CB-11D0-B483-00C04FD90119}"), (void**)(&winDoc));
        if (winDoc)
        {
            // Security:
            // CoInternetSetFeatureEnabled
            // (FEATURE_LOCALMACHINE_LOCKDOWN, SET_FEATURE_ON_PROCESS, TRUE);
            //
488
            document = NULL;
489 490 491
            winDoc->QueryInterface( IID_IHTMLDocument2, (void**)&document );
            IHTMLWindow2 *window = NULL;
            document->get_parentWindow( &window );
492
			documentWin = new QAxObject(document, webViewWin);
493 494 495 496 497 498 499 500
            jScriptWin = new QAxObject(window, webViewWin);
            connect(jScriptWin, SIGNAL(exception(int,QString,QString,QString)), this, SLOT(printWinException(int,QString,QString,QString)));
            jScriptInitialized = true;
        }
        else
        {
            qDebug() << "COULD NOT GET DOCUMENT OBJECT! Aborting";
        }
501
#endif
502
        QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth()));
503 504
        return;
    }
505

506 507
    if (!gEarthInitialized)
    {
508 509 510 511 512
        if (0 == 1)//(!javaScript("isInitialized();").toBool())
        {
            QTimer::singleShot(500, this, SLOT(initializeGoogleEarth()));
            qDebug() << "NOT INITIALIZED, WAITING";
        }
513 514
        else
        {
515 516
            gEarthInitialized = true;

517 518 519 520 521 522 523 524
            // Set home location
            setHome(47.3769, 8.549444, 500);

            // Move to home location
            goHome();

            // Add all MAVs
            QList<UASInterface*> mavs = UASManager::instance()->getUASList();
525
            foreach (UASInterface* currMav, mavs)
526
            {
527
                addUAS(currMav);
528 529
            }

530 531 532
            // Set current UAS
            setActiveUAS(UASManager::instance()->getActiveUAS());

533
            // Add any further MAV automatically
534 535
            connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
            connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
536 537 538 539 540

            // Connect UI signals/slots

            // Follow checkbox
            ui->followAirplaneCheckbox->setChecked(followCamera);
541
            connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool)), Qt::UniqueConnection);
542 543 544

            // Trail checkbox
            ui->trailCheckbox->setChecked(trailEnabled);
545
            connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool)), Qt::UniqueConnection);
546 547 548 549 550

            // Go home
            connect(ui->goHomeButton, SIGNAL(clicked()), this, SLOT(goHome()));

            // Cam distance slider
551
            connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int)), Qt::UniqueConnection);
552
            setViewRangeScaledInt(ui->camDistanceSlider->value());
553

554 555 556 557 558
            // 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);

559 560 561
            // Update waypoint list
            if (mav) updateWaypointList(mav->getUASID());

562 563 564
            // Start update timer
            updateTimer->start(refreshRateMs);

565 566
            // Set current view mode
            setViewMode(currentViewMode);
567 568
            setDistanceMode(ui->camDistanceComboBox->currentIndex());
            enableEditMode(ui->editButton->isChecked());
569 570
            enableAtmosphere(ui->atmosphereCheckBox->isChecked());
            enableDaylight(ui->daylightCheckBox->isChecked());
pixhawk's avatar
pixhawk committed
571
            follow(this->followCamera);
572 573 574 575 576 577
        }
    }
}

void QGCGoogleEarthView::updateState()
{
578 579 580
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
581 582 583 584 585 586 587 588 589 590 591 592 593
    if (gEarthInitialized)
    {
        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();
594
        foreach (UASInterface* currMav, mavs)
595
        {
596 597 598 599 600 601 602
            uasId = currMav->getUASID();
            lat = currMav->getLatitude();
            lon = currMav->getLongitude();
            alt = currMav->getAltitude();
            roll = currMav->getRoll();
            pitch = currMav->getPitch();
            yaw = currMav->getYaw();
603

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

606
            javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
607
                       .arg(uasId)
608 609 610 611 612 613
                       .arg(lat, 0, 'f', 15)
                       .arg(lon, 0, 'f', 15)
                       .arg(alt, 0, 'f', 15)
                       .arg(roll, 0, 'f', 9)
                       .arg(pitch, 0, 'f', 9)
                       .arg(yaw, 0, 'f', 9));
614
        }
615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663


        // 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 = .to
        bool newWaypointPending = documentElement("newWaypointPending").toBool();
        if (newWaypointPending)
        {
            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;
            if (coordsOk)
            {
                // Add new waypoint
                if (mav)
                {
                    int nextIndex = mav->getWaypointManager()->getWaypointList().count();
                    Waypoint* wp = new Waypoint(nextIndex, latitude, longitude, altitude, true);
                    wp->setFrame(MAV_FRAME_GLOBAL);
//                    wp.setLatitude(latitude);
//                    wp.setLongitude(longitude);
//                    wp.setAltitude(altitude);
                    mav->getWaypointManager()->addWaypoint(wp);
                }
            }
            javaScript("setNewWaypointPending(false);");
        }

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

        if (dragWaypointPending)
        {
            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;
664 665

            // UPDATE WAYPOINTS, HOME LOCATION AND OTHER LOCATIONS
666 667
            if (coordsOk)
            {
668 669
                QString idText = documentElement("dragWaypointIndex").toString();
                if (idText == "HOME")
670
                {
671 672 673 674 675 676
                    setHome(latitude, longitude, altitude);
                }
                else
                {
                    // Update waypoint or symbol
                    if (mav)
677
                    {
678 679 680 681 682 683 684 685 686 687 688 689 690
                        QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameWaypointList();

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

                        if (ok && index >= 0 && index < wps.count())
                        {
                            Waypoint* wp = wps.at(index);
                            wp->setLatitude(latitude);
                            wp->setLongitude(longitude);
                            wp->setAltitude(altitude);
                            mav->getWaypointManager()->notifyOfChange(wp);
                        }
691 692 693 694 695 696 697 698 699 700 701
                    }
                }
            }
            else
            {
                // If coords were not ok, move the view in google earth back
                // to last acceptable location
                updateWaypointList(mav->getUASID());
            }
            javaScript("setDragWaypointPending(false);");
        }
702 703 704 705 706 707 708 709 710 711 712 713 714 715 716
    }
}


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