QGCGoogleEarthView.cc 12.1 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16
#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>
#include "QGCWebPage.h"
#endif

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

#include "QGC.h"
24 25 26 27 28 29 30 31
#include "ui_QGCGoogleEarthView.h"
#include "QGCGoogleEarthView.h"

#define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_")

QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
        QWidget(parent),
        updateTimer(new QTimer(this)),
32
        refreshRateMs(40),
33 34 35 36
        mav(NULL),
        followCamera(true),
        trailEnabled(true),
        webViewInitialized(false),
37
        jScriptInitialized(false),
38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54
        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


55 56 57 58 59 60 61 62 63
    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();
64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92


#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);
    connect(webViewMac, SIGNAL(loadFinished(bool)), this, SLOT(initializeGoogleEarth(bool)));
#endif

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

    connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState()));
}

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

102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117
/**
 * @param range in centimeters
 */
void QGCGoogleEarthView::setViewRangeScaledInt(int range)
{
    setViewRange(range/100.0f);
}

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

118 119
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
120 121 122 123 124 125 126 127 128 129 130 131
    // 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()));

132
    //javaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg("0"));
133 134
    // Automatically receive further position updates
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
135 136 137 138 139 140 141
}

void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
{
    if (uas)
    {
        mav = uas;
142
        javaScript(QString("setCurrAircraft(%1);").arg(uas->getUASID()));
143 144 145
    }
}

146
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
147 148
{
    Q_UNUSED(usec);
149
    javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
150

151
    //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);
152 153 154 155
}

void QGCGoogleEarthView::showTrail(bool state)
{
156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175
    // Check if the current trail has to be hidden
    if (trailEnabled && !state)
    {
        QList<UASInterface*> mavs = UASManager::instance()->getUASList();
        foreach (UASInterface* currMav, mavs)
        {
            javaScript(QString("hideTrail(%1);").arg(currMav->getUASID()));
        }
    }

    // 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;
176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195
    ui->trailCheckbox->setChecked(state);
}

void QGCGoogleEarthView::showWaypoints(bool state)
{

}

void QGCGoogleEarthView::follow(bool follow)
{
    ui->followAirplaneCheckbox->setChecked(follow);
    followCamera = follow;
}

void QGCGoogleEarthView::goHome()
{
    // Disable follow and update
    follow(false);
    updateState();
    // Go to home location
196
    javaScript("goHome();");
197 198 199 200
}

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

204 205 206 207 208
void QGCGoogleEarthView::hideEvent(QHideEvent* event)
{
    Q_UNUSED(event) updateTimer->stop();
}

209 210 211 212
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
213
    Q_UNUSED(event)
214
    {
215
        // Enable widget, initialize on first run
216 217 218

        // FIXME Re-inits now on every visibility change
        //if (!webViewInitialized)
219
        {
220
#if (defined Q_OS_MAC)
221 222 223
            webViewMac->setPage(new QGCWebPage(webViewMac));
            webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
            webViewMac->load(QUrl("earth.html"));
224 225 226
#endif

#ifdef _MSC_VER
227 228
            //webViewWin->dynamicCall("GoHome()");
            webViewWin->dynamicCall("Navigate(const QString&)", QApplication::applicationDirPath() + "/earth.html");
229 230
#endif

231 232 233
            webViewInitialized = true;
            // Reloading the webpage, this resets Google Earth
            gEarthInitialized = false;
234

235 236 237
            QTimer::singleShot(2000, this, SLOT(initializeGoogleEarth()));
            updateTimer->start(refreshRateMs);
        }
238 239 240
    }
}

241 242
void QGCGoogleEarthView::printWinException(int no, QString str1, QString str2, QString str3)
{
243
    qDebug() << no << str1 << str2 << str3;
244 245 246 247 248
}

QVariant QGCGoogleEarthView::javaScript(QString javaScript)
{
#ifdef Q_OS_MAC
249
    return webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript);
250 251
#endif
#ifdef _MSC_VER
252 253 254 255 256 257 258 259 260 261 262 263
    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);
    }
264 265 266
#endif
}

267 268
void QGCGoogleEarthView::initializeGoogleEarth()
{
269 270 271 272
    if (!jScriptInitialized)
    {
#ifdef Q_OS_MAC
        jScriptInitialized = true;
273
#endif
274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300
#ifdef _MSC_VER
        QAxObject* doc = webViewWin->querySubObject("Document()");
        IDispatch* Disp;
        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";
        }
301
#endif
302 303 304
        QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth()));
        return;
    }
305

306 307
    if (!gEarthInitialized)
    {
308 309 310 311 312
        if (0 == 1)//(!javaScript("isInitialized();").toBool())
        {
            QTimer::singleShot(500, this, SLOT(initializeGoogleEarth()));
            qDebug() << "NOT INITIALIZED, WAITING";
        }
313 314
        else
        {
315 316 317 318 319 320 321 322
            // Set home location
            setHome(47.3769, 8.549444, 500);

            // Move to home location
            goHome();

            // Add all MAVs
            QList<UASInterface*> mavs = UASManager::instance()->getUASList();
323
            foreach (UASInterface* currMav, mavs)
324
            {
325
                addUAS(currMav);
326 327
            }

328 329 330
            // Set current UAS
            setActiveUAS(UASManager::instance()->getActiveUAS());

331 332
            // Add any further MAV automatically
            connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350
            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());
351 352 353 354 355 356 357 358

            gEarthInitialized = true;
        }
    }
}

void QGCGoogleEarthView::updateState()
{
359 360 361
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
362 363 364 365 366 367 368 369 370 371 372 373 374
    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();
375
        foreach (UASInterface* currMav, mavs)
376
        {
377 378 379 380 381 382 383
            uasId = currMav->getUASID();
            lat = currMav->getLatitude();
            lon = currMav->getLongitude();
            alt = currMav->getAltitude();
            roll = currMav->getRoll();
            pitch = currMav->getPitch();
            yaw = currMav->getYaw();
384

385
            javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
386
                       .arg(uasId)
387 388 389 390 391 392
                       .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));
393 394 395 396
        }

        if (followCamera)
        {
397
            javaScript(QString("updateFollowAircraft()"));
398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413
        }
    }
}


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