QGCGoogleEarthView.cc 19.6 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 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56
        gEarthInitialized(false),
#if (defined Q_OS_MAC)
        webViewMac(new QWebView(this)),
#endif
#ifdef _MSC_VER
        webViewWin(new QGCWebAxWidget(this)),
#endif
#if (defined _MSC_VER)
        ui(new Ui::QGCGoogleEarthView)
#else
        ui(new Ui::QGCGoogleEarthView)
#endif
{
#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 89 90 91 92 93 94 95
}

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

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

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

122 123 124 125 126 127 128 129
/**
 * @param range in meters (SI-units)
 */
void QGCGoogleEarthView::setViewRange(float range)
{
    javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5));
}

130 131
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
132 133 134 135 136 137 138 139 140 141 142 143
    // 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()));

144 145
    // 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
146 147 148 149 150 151
    // 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
152 153 154 155 156 157 158
}

void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
{
    if (uas)
    {
        mav = uas;
159
        javaScript(QString("setCurrAircraft(%1);").arg(uas->getUASID()));
160 161 162
    }
}

pixhawk's avatar
pixhawk committed
163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184
/**
 * 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
185 186
            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()));
            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
187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207
        }
    }
}

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

pixhawk's avatar
pixhawk committed
210 211 212 213 214 215 216 217
        // Load all existing waypoints into map view
        foreach (Waypoint* wp, wpList)
        {
            updateWaypoint(uas, wp);
        }
    }
}

218
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
219 220
{
    Q_UNUSED(usec);
lm's avatar
lm committed
221
    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));
222

lm's avatar
lm committed
223
    //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);
224 225 226 227
}

void QGCGoogleEarthView::showTrail(bool state)
{
228 229 230 231 232 233
    // Check if the current trail has to be hidden
    if (trailEnabled && !state)
    {
        QList<UASInterface*> mavs = UASManager::instance()->getUASList();
        foreach (UASInterface* currMav, mavs)
        {
234
            javaScript(QString("hideTrail(%1);").arg(currMav->getUASID()));
235 236 237 238 239 240 241 242 243 244 245 246 247
        }
    }

    // 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;
248 249 250 251 252
    ui->trailCheckbox->setChecked(state);
}

void QGCGoogleEarthView::showWaypoints(bool state)
{
pixhawk's avatar
pixhawk committed
253
    waypointsEnabled = state;
254 255 256 257 258 259
}

void QGCGoogleEarthView::follow(bool follow)
{
    ui->followAirplaneCheckbox->setChecked(follow);
    followCamera = follow;
pixhawk's avatar
pixhawk committed
260
    if (gEarthInitialized) javaScript(QString("setFollowEnabled(%1)").arg(follow));
261 262 263 264 265 266 267 268
}

void QGCGoogleEarthView::goHome()
{
    // Disable follow and update
    follow(false);
    updateState();
    // Go to home location
269
    javaScript("goHome();");
270 271 272 273
}

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

277 278
void QGCGoogleEarthView::hideEvent(QHideEvent* event)
{
279 280
    Q_UNUSED(event);
    updateTimer->stop();
281 282
}

283 284 285 286
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
287
    Q_UNUSED(event)
288
        // Enable widget, initialize on first run
289

290
        if (!webViewInitialized)
291
        {
292
#if (defined Q_OS_MAC)
293 294
            webViewMac->setPage(new QGCWebPage(webViewMac));
            webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
pixhawk's avatar
pixhawk committed
295
            webViewMac->load(QUrl(QCoreApplication::applicationDirPath()+"/earth.html"));
296 297 298
#endif

#ifdef _MSC_VER
299 300
            //webViewWin->dynamicCall("GoHome()");
            webViewWin->dynamicCall("Navigate(const QString&)", QApplication::applicationDirPath() + "/earth.html");
301 302
#endif

303 304 305
            webViewInitialized = true;
            // Reloading the webpage, this resets Google Earth
            gEarthInitialized = false;
306

307
            QTimer::singleShot(10000, this, SLOT(initializeGoogleEarth()));
308 309 310
        }
        else
        {
311 312
            updateTimer->start(refreshRateMs);
        }
313 314
}

315 316
void QGCGoogleEarthView::printWinException(int no, QString str1, QString str2, QString str3)
{
317
    qDebug() << no << str1 << str2 << str3;
318 319 320 321 322
}

QVariant QGCGoogleEarthView::javaScript(QString javaScript)
{
#ifdef Q_OS_MAC
323
    return webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript);
324 325
#endif
#ifdef _MSC_VER
326 327 328 329 330 331 332 333 334 335 336 337
    if(!jScriptInitialized)
    {
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
        return QVariant(false);
    }
    else
    {
        QVariantList params;
        params.append(javaScript);
        params.append("JScript");
        return jScriptWin->dynamicCall("execScript(QString, QString)", params);
    }
338 339 340
#endif
}

341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364
QVariant QGCGoogleEarthView::documentElement(QString name)
{
#ifdef Q_OS_MAC
    QString javaScript("getGlobal(%1)");
    QVariant result = webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript.arg(name));
    //qDebug() << "DOC ELEM:" << name << ":" << result;
    return result;
#endif
#ifdef _MSC_VER
    if(!jScriptInitialized)
    {
        qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
        return QVariant(false);
    }
    else
    {
        //QVariantList params;
        //params.append(javaScript);
        //params.append("JScript");
        //return jScriptWin->dynamicCall("execScript(QString, QString)", params);
    }
#endif
}

365 366
void QGCGoogleEarthView::initializeGoogleEarth()
{
367 368 369 370
    if (!jScriptInitialized)
    {
#ifdef Q_OS_MAC
        jScriptInitialized = true;
371
#endif
372 373
#ifdef _MSC_VER
        QAxObject* doc = webViewWin->querySubObject("Document()");
374
        //IDispatch* Disp;
375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398
        IDispatch* winDoc = NULL;

        //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);
            //
            IHTMLDocument2* document = NULL;
            winDoc->QueryInterface( IID_IHTMLDocument2, (void**)&document );
            IHTMLWindow2 *window = NULL;
            document->get_parentWindow( &window );

            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";
        }
399
#endif
400
        QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth()));
401 402
        return;
    }
403

404 405
    if (!gEarthInitialized)
    {
406 407 408 409 410
        if (0 == 1)//(!javaScript("isInitialized();").toBool())
        {
            QTimer::singleShot(500, this, SLOT(initializeGoogleEarth()));
            qDebug() << "NOT INITIALIZED, WAITING";
        }
411 412
        else
        {
413 414 415 416 417 418 419 420
            // Set home location
            setHome(47.3769, 8.549444, 500);

            // Move to home location
            goHome();

            // Add all MAVs
            QList<UASInterface*> mavs = UASManager::instance()->getUASList();
421
            foreach (UASInterface* currMav, mavs)
422
            {
423
                addUAS(currMav);
424 425
            }

426 427 428
            // Set current UAS
            setActiveUAS(UASManager::instance()->getActiveUAS());

429 430
            // Add any further MAV automatically
            connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448
            connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));

            // Connect UI signals/slots

            // Follow checkbox
            ui->followAirplaneCheckbox->setChecked(followCamera);
            connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool)));

            // Trail checkbox
            ui->trailCheckbox->setChecked(trailEnabled);
            connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool)));

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

            // Cam distance slider
            connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int)));
            setViewRangeScaledInt(ui->camDistanceSlider->value());
449

450 451 452
            // Update waypoint list
            if (mav) updateWaypointList(mav->getUASID());

453 454 455
            // Start update timer
            updateTimer->start(refreshRateMs);

pixhawk's avatar
pixhawk committed
456 457
            follow(this->followCamera);

458 459 460 461 462 463 464
            gEarthInitialized = true;
        }
    }
}

void QGCGoogleEarthView::updateState()
{
465 466 467
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
468 469 470 471 472 473 474 475 476 477 478 479 480
    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();
481
        foreach (UASInterface* currMav, mavs)
482
        {
483 484 485 486 487 488 489
            uasId = currMav->getUASID();
            lat = currMav->getLatitude();
            lon = currMav->getLongitude();
            alt = currMav->getAltitude();
            roll = currMav->getRoll();
            pitch = currMav->getPitch();
            yaw = currMav->getYaw();
490

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

493
            javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
494
                       .arg(uasId)
495 496 497 498 499 500
                       .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));
501
        }
502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586


        // 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;
            if (coordsOk)
            {
                // Add new waypoint
                if (mav)
                {
                    QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameWaypointList();

                    QString idText = documentElement("dragWaypointIndex").toString();

                    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);
                        //                    Waypoint wp;
                        //                    wp.setFrame(MAV_FRAME_GLOBAL);
                        //                    wp.setLatitude(latitude);
                        //                    wp.setLongitude(longitude);
                        //                    wp.setAltitude(altitude);
                        //                    mav->getWaypointManager()->addWaypoint(wp);
                        mav->getWaypointManager()->notifyOfChange(wp);
                    }
                }
            }
            else
            {
                // If coords were not ok, move the view in google earth back
                // to last acceptable location
                updateWaypointList(mav->getUASID());
            }
            javaScript("setDragWaypointPending(false);");
        }
587 588 589 590 591 592 593 594 595 596 597 598 599 600 601
    }
}


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