QGCGoogleEarthView.cc 25.7 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 35 36

#define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_")

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

57 58 59 60 61 62 63 64 65
    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();
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 103 104 105 106 107
#if (defined Q_OS_MAC)
        delete webViewMac;
#endif
#ifdef _MSC_VER
        delete webViewWin;
#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 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
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));
}

196 197
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
198 199 200 201 202 203 204 205 206 207 208 209
    // 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()));

210 211
    // 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
212 213 214 215 216 217
    // 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
218 219 220 221 222 223 224
}

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

pixhawk's avatar
pixhawk committed
230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251
/**
 * 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
252
            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()));
253
            //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
254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
        }
    }
}

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

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

285
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
286 287
{
    Q_UNUSED(usec);
lm's avatar
lm committed
288
    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));
289

lm's avatar
lm committed
290
    //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);
291 292
}

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

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

    // 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;
324 325 326 327 328
    ui->trailCheckbox->setChecked(state);
}

void QGCGoogleEarthView::showWaypoints(bool state)
{
pixhawk's avatar
pixhawk committed
329
    waypointsEnabled = state;
330 331 332 333 334
}

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

void QGCGoogleEarthView::goHome()
{
    // Disable follow and update
    follow(false);
    updateState();
    // Go to home location
356
    javaScript("goHome();");
357 358 359 360
}

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

365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397
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);
    if (ok && !text.isEmpty())
    {
        QStringList split = text.split(",");
        if (split.length() == 2)
        {
            bool convert;
            double latitude = split.first().toDouble(&convert);
            ok &= convert;
            double longitude = split.last().toDouble(&convert);
            ok &= convert;

            if (ok)
            {
                javaScript(QString("setLookAtLatLon(%1,%2);").arg(latitude, 0, 'f', 15).arg(longitude, 0, 'f', 15));
            }
        }
    }
}

398 399
void QGCGoogleEarthView::hideEvent(QHideEvent* event)
{
400 401
    Q_UNUSED(event);
    updateTimer->stop();
402 403
}

404 405 406 407
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
408
    Q_UNUSED(event)
409
        // Enable widget, initialize on first run
410

411
        if (!webViewInitialized)
412
        {
413
#if (defined Q_OS_MAC)
414 415
            webViewMac->setPage(new QGCWebPage(webViewMac));
            webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
pixhawk's avatar
pixhawk committed
416
            webViewMac->load(QUrl(QCoreApplication::applicationDirPath()+"/earth.html"));
417 418 419
#endif

#ifdef _MSC_VER
420 421
            //webViewWin->dynamicCall("GoHome()");
            webViewWin->dynamicCall("Navigate(const QString&)", QApplication::applicationDirPath() + "/earth.html");
422 423
#endif

424 425 426
            webViewInitialized = true;
            // Reloading the webpage, this resets Google Earth
            gEarthInitialized = false;
427

428
            QTimer::singleShot(3000, this, SLOT(initializeGoogleEarth()));
429 430 431
        }
        else
        {
432 433
            updateTimer->start(refreshRateMs);
        }
434 435
}

436 437
void QGCGoogleEarthView::printWinException(int no, QString str1, QString str2, QString str3)
{
438
    qDebug() << no << str1 << str2 << str3;
439 440 441 442 443
}

QVariant QGCGoogleEarthView::javaScript(QString javaScript)
{
#ifdef Q_OS_MAC
lm's avatar
lm committed
444
    if (!jScriptInitialized)
445 446 447 448 449 450 451
    {
        return QVariant(false);
    }
    else
    {
        return webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript);
    }
452 453
#endif
#ifdef _MSC_VER
454 455 456 457 458 459 460 461 462 463
    if(!jScriptInitialized)
    {
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
        return QVariant(false);
    }
    else
    {
        QVariantList params;
        params.append(javaScript);
        params.append("JScript");
464 465
        QVariant result = jScriptWin->dynamicCall("execScript(QString, QString)", params);
        return result;
466
    }
467 468 469
#endif
}

470 471 472 473 474 475 476 477 478 479 480 481 482 483
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";
    }
    else
    {
484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519
        if (documentWin)
        {
            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;
            if (element)
            {
                //element->get_innerHTML(&elemString);
                VARIANT var;
                var.vt = VT_BSTR;
                HRESULT res = element->getAttribute(L"value", 0, &var);
                if (SUCCEEDED(res) && (var.vt != VT_NULL))
                {
                    QByteArray typeName;
                    QVariant qtValue = VARIANTToQVariant(var,typeName);
                    return qtValue;
                }
                else
                {
                    qDebug() << __FILE__ << __LINE__ << "JAVASCRIPT ATTRIBUTE" << name << "NOT FOUND";
                }
            }
            else
            {
                qDebug() << __FILE__ << __LINE__ << "DID NOT GET HTML ELEMENT" << name;
            }
        }
520
    }
521
    return QVariant(0);
522 523 524
#endif
}

525 526
void QGCGoogleEarthView::initializeGoogleEarth()
{
527 528 529 530
    if (!jScriptInitialized)
    {
#ifdef Q_OS_MAC
        jScriptInitialized = true;
531
#endif
532 533
#ifdef _MSC_VER
        QAxObject* doc = webViewWin->querySubObject("Document()");
534
        //IDispatch* Disp;
535
        IDispatch* winDoc = NULL;
536
        IHTMLDocument2* document = NULL;
537 538 539 540 541 542

        //332C4425-26CB-11D0-B483-00C04FD90119 IHTMLDocument2
        //25336920-03F9-11CF-8FD0-00AA00686F13 HTMLDocument
        doc->queryInterface(QUuid("{332C4425-26CB-11D0-B483-00C04FD90119}"), (void**)(&winDoc));
        if (winDoc)
        {
543
            document = NULL;
544 545 546
            winDoc->QueryInterface( IID_IHTMLDocument2, (void**)&document );
            IHTMLWindow2 *window = NULL;
            document->get_parentWindow( &window );
547
            documentWin = new QAxObject(document, webViewWin);
548 549 550 551 552 553 554 555
            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";
        }
556
#endif
557
        QTimer::singleShot(1500, this, SLOT(initializeGoogleEarth()));
558 559
        return;
    }
560

561 562
    if (!gEarthInitialized)
    {
563
		if (!documentElement("initialized").toBool())
564
        {
565
            QTimer::singleShot(300, this, SLOT(initializeGoogleEarth()));
566 567
            qDebug() << "NOT INITIALIZED, WAITING";
        }
568 569
        else
        {
570 571
            gEarthInitialized = true;

572
            // Set home location
573
            setHome(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
574 575 576

            // Add all MAVs
            QList<UASInterface*> mavs = UASManager::instance()->getUASList();
577
            foreach (UASInterface* currMav, mavs)
578
            {
579
                addUAS(currMav);
580 581
            }

582 583 584
            // Set current UAS
            setActiveUAS(UASManager::instance()->getActiveUAS());

585
            // Add any further MAV automatically
586 587
            connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
            connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
588 589 590 591 592

            // Connect UI signals/slots

            // Follow checkbox
            ui->followAirplaneCheckbox->setChecked(followCamera);
593
            connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool)), Qt::UniqueConnection);
594 595 596

            // Trail checkbox
            ui->trailCheckbox->setChecked(trailEnabled);
597
            connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool)), Qt::UniqueConnection);
598 599 600

            // Go home
            connect(ui->goHomeButton, SIGNAL(clicked()), this, SLOT(goHome()));
601 602 603 604 605 606 607 608 609
            // 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()));
610 611

            // Cam distance slider
612
            connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int)), Qt::UniqueConnection);
613
            setViewRangeScaledInt(ui->camDistanceSlider->value());
614

615 616 617 618 619
            // 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);

620 621 622
            // Update waypoint list
            if (mav) updateWaypointList(mav->getUASID());

623 624 625
            // Start update timer
            updateTimer->start(refreshRateMs);

626 627
            // Set current view mode
            setViewMode(currentViewMode);
628 629
            setDistanceMode(ui->camDistanceComboBox->currentIndex());
            enableEditMode(ui->editButton->isChecked());
630 631
            enableAtmosphere(ui->atmosphereCheckBox->isChecked());
            enableDaylight(ui->daylightCheckBox->isChecked());
pixhawk's avatar
pixhawk committed
632
            follow(this->followCamera);
633 634 635

            // Move to home location
            goHome();
636 637 638 639 640 641
        }
    }
}

void QGCGoogleEarthView::updateState()
{
642 643 644
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
645 646 647 648 649 650 651 652 653 654 655 656 657
    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();
658
        foreach (UASInterface* currMav, mavs)
659
        {
660 661 662 663 664 665 666
            uasId = currMav->getUASID();
            lat = currMav->getLatitude();
            lon = currMav->getLongitude();
            alt = currMav->getAltitude();
            roll = currMav->getRoll();
            pitch = currMav->getPitch();
            yaw = currMav->getYaw();
667

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

670
            javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
671
                       .arg(uasId)
672 673 674 675 676 677
                       .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));
678
        }
679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727


        // 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;
728 729

            // UPDATE WAYPOINTS, HOME LOCATION AND OTHER LOCATIONS
730 731
            if (coordsOk)
            {
732 733
                QString idText = documentElement("dragWaypointIndex").toString();
                if (idText == "HOME")
734
                {
735 736 737
                    qDebug() << "HOME UPDATED!";
                    UASManager::instance()->setHomePosition(latitude, longitude, altitude);
                    ui->setHomeButton->setChecked(false);
738 739 740 741 742
                }
                else
                {
                    // Update waypoint or symbol
                    if (mav)
743
                    {
744 745 746 747 748 749 750 751 752 753 754 755 756
                        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);
                        }
757 758 759 760 761 762 763 764 765 766 767
                    }
                }
            }
            else
            {
                // If coords were not ok, move the view in google earth back
                // to last acceptable location
                updateWaypointList(mav->getUASID());
            }
            javaScript("setDragWaypointPending(false);");
        }
768 769 770 771 772 773 774 775 776 777 778 779 780 781 782
    }
}


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