Commit 4e86e85f authored by Don Gagne's avatar Don Gagne

Merge pull request #1404 from DonLakeFlyer/RemoveGoogleEarth

Remove GoogleEarth support
parents 48416b2c 244aff2e
......@@ -162,46 +162,6 @@ OSGDependency {
src/ui/map3D/ImageryParamDialog.cc
}
#
# [OPTIONAL] Google Earth dependency. Provides Google Earth view to supplement 2D map view.
# Only supported on Mac and Windows where Google Earth can be installed.
#
GoogleEarthDisableOverride {
contains(DEFINES, DISABLE_GOOGLE_EARTH) {
message("Skipping support for Google Earth view (manual override from command line)")
DEFINES -= DISABLE_GOOGLE_EARTH
}
# Otherwise the user can still disable this feature in the user_config.pri file.
else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_GOOGLE_EARTH) {
message("Skipping support for Google Earth view (manual override from user_config.pri)")
} else:MacBuild {
message("Including support for Google Earth view")
DEFINES += QGC_GOOGLE_EARTH_ENABLED
HEADERS += src/ui/map3D/QGCGoogleEarthView.h \
src/ui/map3D/QGCWebPage.h \
src/ui/QGCWebView.h
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/QGCWebView.cc
FORMS += src/ui/QGCWebView.ui
} else:WindowsBuild {
message("Including support for Google Earth view")
DEFINES += QGC_GOOGLE_EARTH_ENABLED
HEADERS += src/ui/map3D/QGCGoogleEarthView.h \
src/ui/map3D/QGCWebPage.h \
src/ui/QGCWebView.h
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/QGCWebView.cc
FORMS += src/ui/QGCWebView.ui
QT += axcontainer
} else {
message("Skipping support for Google Earth view (unsupported platform)")
}
} else {
message("Skipping support for Google Earth due to Issue 1157")
}
#
# [REQUIRED] EIGEN matrix library
# NOMINMAX constant required to make internal min/max work.
......
......@@ -125,11 +125,6 @@ contains(DEFINES, QGC_NOTIFY_TUNES_ENABLED) {
QT += multimedia
}
!contains(DEFINES, DISABLE_GOOGLE_EARTH) {
QT += webkit webkitwidgets
}
# testlib is needed even in release flavor for QSignalSpy support
QT += testlib
......@@ -291,7 +286,6 @@ FORMS += \
src/ui/QGCSensorSettingsWidget.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QMap3D.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \
......
......@@ -263,20 +263,18 @@ MainWindow::MainWindow(QSplashScreen* splashScreen)
_ui.actionMissionView->setShortcut(QApplication::translate("MainWindow", "Meta+2", 0));
_ui.actionFlightView->setShortcut(QApplication::translate("MainWindow", "Meta+3", 0));
_ui.actionEngineersView->setShortcut(QApplication::translate("MainWindow", "Meta+4", 0));
_ui.actionGoogleEarthView->setShortcut(QApplication::translate("MainWindow", "Meta+5", 0));
_ui.actionLocal3DView->setShortcut(QApplication::translate("MainWindow", "Meta+6", 0));
_ui.actionTerminalView->setShortcut(QApplication::translate("MainWindow", "Meta+7", 0));
_ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Meta+8", 0));
_ui.actionLocal3DView->setShortcut(QApplication::translate("MainWindow", "Meta+5", 0));
_ui.actionTerminalView->setShortcut(QApplication::translate("MainWindow", "Meta+6", 0));
_ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Meta+7", 0));
_ui.actionFullscreen->setShortcut(QApplication::translate("MainWindow", "Meta+Return", 0));
#else
_ui.actionSetup->setShortcut(QApplication::translate("MainWindow", "Ctrl+1", 0));
_ui.actionMissionView->setShortcut(QApplication::translate("MainWindow", "Ctrl+2", 0));
_ui.actionFlightView->setShortcut(QApplication::translate("MainWindow", "Ctrl+3", 0));
_ui.actionEngineersView->setShortcut(QApplication::translate("MainWindow", "Ctrl+4", 0));
_ui.actionGoogleEarthView->setShortcut(QApplication::translate("MainWindow", "Ctrl+5", 0));
_ui.actionLocal3DView->setShortcut(QApplication::translate("MainWindow", "Ctrl+6", 0));
_ui.actionTerminalView->setShortcut(QApplication::translate("MainWindow", "Ctrl+7", 0));
_ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Ctrl+8", 0));
_ui.actionLocal3DView->setShortcut(QApplication::translate("MainWindow", "Ctrl+5", 0));
_ui.actionTerminalView->setShortcut(QApplication::translate("MainWindow", "Ctrl+6", 0));
_ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Ctrl+7", 0));
_ui.actionFullscreen->setShortcut(QApplication::translate("MainWindow", "Ctrl+Return", 0));
#endif
......@@ -486,16 +484,6 @@ void MainWindow::_buildTerminalView(void)
}
}
void MainWindow::_buildGoogleEarthView(void)
{
#ifdef QGC_GOOGLE_EARTH_ENABLED
if (!_googleEarthView) {
_googleEarthView = new QGCGoogleEarthView(this);
_googleEarthView->setVisible(false);
}
#endif
}
void MainWindow::_buildLocal3DView(void)
{
#ifdef QGC_OSG_ENABLED
......@@ -731,9 +719,6 @@ void MainWindow::loadSettings()
case VIEW_TERMINAL:
#ifdef QGC_OSG_ENABLED
case VIEW_LOCAL3D:
#endif
#ifdef QGC_GOOGLE_EARTH_ENABLED
case VIEW_GOOGLEEARTH:
#endif
_currentView = currentViewCandidate;
break;
......@@ -837,14 +822,10 @@ void MainWindow::connectCommonActions()
perspectives->addAction(_ui.actionMissionView);
perspectives->addAction(_ui.actionSetup);
perspectives->addAction(_ui.actionTerminalView);
perspectives->addAction(_ui.actionGoogleEarthView);
perspectives->addAction(_ui.actionLocal3DView);
perspectives->setExclusive(true);
/* Hide the actions that are not relevant */
#ifndef QGC_GOOGLE_EARTH_ENABLED
_ui.actionGoogleEarthView->setVisible(false);
#endif
#ifndef QGC_OSG_ENABLED
_ui.actionLocal3DView->setVisible(false);
#endif
......@@ -880,11 +861,6 @@ void MainWindow::connectCommonActions()
_ui.actionTerminalView->setChecked(true);
_ui.actionTerminalView->activate(QAction::Trigger);
}
if (_currentView == VIEW_GOOGLEEARTH)
{
_ui.actionGoogleEarthView->setChecked(true);
_ui.actionGoogleEarthView->activate(QAction::Trigger);
}
if (_currentView == VIEW_LOCAL3D)
{
_ui.actionLocal3DView->setChecked(true);
......@@ -917,8 +893,6 @@ void MainWindow::connectCommonActions()
connect(_ui.actionSimulationView, SIGNAL(triggered()), this, SLOT(loadSimulationView()));
connect(_ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
connect(_ui.actionMissionView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
connect(_ui.actionSetup,SIGNAL(triggered()),this,SLOT(loadSetupView()));
connect(_ui.actionGoogleEarthView, SIGNAL(triggered()), this, SLOT(loadGoogleEarthView()));
connect(_ui.actionLocal3DView, SIGNAL(triggered()), this, SLOT(loadLocal3DView()));
connect(_ui.actionTerminalView,SIGNAL(triggered()),this,SLOT(loadTerminalView()));
......@@ -1121,11 +1095,6 @@ void MainWindow::_loadCurrentViewState(void)
centerView = _terminalView;
break;
case VIEW_GOOGLEEARTH:
_buildGoogleEarthView();
centerView = _googleEarthView;
break;
case VIEW_LOCAL3D:
_buildLocal3DView();
centerView = _local3DView;
......@@ -1267,17 +1236,6 @@ void MainWindow::loadTerminalView()
}
}
void MainWindow::loadGoogleEarthView()
{
if (_currentView != VIEW_GOOGLEEARTH)
{
_storeCurrentViewState();
_currentView = VIEW_GOOGLEEARTH;
_ui.actionGoogleEarthView->setChecked(true);
_loadCurrentViewState();
}
}
void MainWindow::loadLocal3DView()
{
if (_currentView != VIEW_LOCAL3D)
......
......@@ -57,9 +57,6 @@ This file is part of the QGROUNDCONTROL project
#include "HDDisplay.h"
#include "HSIDisplay.h"
#include "opmapcontrol.h"
#ifdef QGC_GOOGLE_EARTH_ENABLED
#include "QGCGoogleEarthView.h"
#endif
#include "MainToolBar.h"
#include "LogCompressor.h"
......@@ -159,8 +156,6 @@ public slots:
void loadOperatorView();
/** @brief Load Terminal Console views */
void loadTerminalView();
/** @brief Load Google Earth View */
void loadGoogleEarthView();
/** @brief Load local 3D view */
void loadLocal3DView();
/** @brief Manage Links */
......@@ -229,7 +224,6 @@ protected:
VIEW_SETUP, // Setup view. Used for initializing the system for operation. Includes UI for calibration, firmware updating/checking, and parameter modifcation.
VIEW_TERMINAL, // Terminal interface. Used for communicating with the remote system, usually in a special configuration input mode.
VIEW_LOCAL3D, // A local 3D view. Provides a local 3D view that makes visualizing 3D attitude/orientation/pose easy while in operation.
VIEW_GOOGLEEARTH // 3D Google Earth view. A 3D terrain view, though the vehicle is still 2D.
} VIEW_SECTIONS;
/** @brief Catch window resize events */
......@@ -247,9 +241,6 @@ protected:
QPointer<Linecharts> linechartWidget;
#ifdef QGC_OSG_ENABLED
QPointer<QWidget> q3DWidget;
#endif
#ifdef QGC_GOOGLE_EARTH_ENABLED
QPointer<QGCGoogleEarthView> earthWidget;
#endif
QPointer<QGCFirmwareUpdate> firmwareUpdateWidget;
......@@ -312,7 +303,6 @@ private:
QPointer<QWidget> _engineeringView;
QPointer<QWidget> _simView;
QPointer<QWidget> _terminalView;
QPointer<QWidget> _googleEarthView;
QPointer<QWidget> _local3DView;
// Dock widget names
......@@ -342,7 +332,6 @@ private:
void _buildEngineeringView(void);
void _buildSimView(void);
void _buildTerminalView(void);
void _buildGoogleEarthView(void);
void _buildLocal3DView(void);
void _storeCurrentViewState(void);
......
......@@ -97,7 +97,6 @@
<addaction name="actionLoadCustomWidgetFile"/>
<addaction name="separator"/>
</widget>
<addaction name="actionGoogleEarthView"/>
<addaction name="actionLocal3DView"/>
<addaction name="actionTerminalView"/>
<addaction name="actionSimulationView"/>
......@@ -328,14 +327,6 @@
<string>Terminal</string>
</property>
</action>
<action name="actionGoogleEarthView">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Google Earth</string>
</property>
</action>
<action name="actionLocal3DView">
<property name="checkable">
<bool>true</bool>
......
#include <QApplication>
#include <QDir>
#include <QShowEvent>
#include <QSettings>
#include <QInputDialog>
#include <QDebug>
#include <QFile>
#include <QTextStream>
#include "UASManager.h"
#ifdef Q_OS_MAC
#include <QWebFrame>
#include <QWebPage>
#include <QWebElement>
#include "QGCWebPage.h"
#endif
#ifdef _MSC_VER
#include <QAxObject>
#include <QUuid>
#include <mshtml.h>
#include <comdef.h>
#include <qaxtypes.h>
#endif
#include "QGC.h"
#include "ui_QGCGoogleEarthView.h"
#include "QGCGoogleEarthView.h"
#include "UASWaypointManager.h"
#define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_")
QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
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),
#if (defined Q_OS_MAC)
webViewMac(new QWebView(this)),
#endif
#ifdef _MSC_VER
webViewWin(new QGCWebAxWidget(this)),
documentWin(NULL),
#endif
ui(new Ui::QGCGoogleEarthView)
{
#ifdef _MSC_VER
// Create layout and attach webViewWin
// 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();
#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()));
connect(ui->resetButton, SIGNAL(clicked()), this, SLOT(reloadHTML()));
connect(ui->changeViewButton, SIGNAL(clicked()), this, SLOT(toggleViewMode()));
connect(ui->clearTrailsButton, SIGNAL(clicked()), this, SLOT(clearTrails()));
connect(ui->atmosphereCheckBox, SIGNAL(clicked(bool)), this, SLOT(enableAtmosphere(bool)));
connect(ui->daylightCheckBox, SIGNAL(clicked(bool)), this, SLOT(enableDaylight(bool)));
connect(UASManager::instance(), SIGNAL(homePositionChanged(double,double,double)), this, SLOT(setHome(double,double,double)));
}
QGCGoogleEarthView::~QGCGoogleEarthView()
{
QSettings settings;
settings.setValue(QGCGOOGLEEARTHVIEWSETTINGS + "follow", followCamera);
settings.setValue(QGCGOOGLEEARTHVIEWSETTINGS + "trail", trailEnabled);
settings.sync();
#if (defined Q_OS_MAC)
delete webViewMac;
#endif
#ifdef _MSC_VER
delete webViewWin;
#endif
delete ui;
}
/**
* @param range in centimeters
*/
void QGCGoogleEarthView::setViewRangeScaledInt(int range)
{
setViewRange(range/100.0f);
}
void QGCGoogleEarthView::reloadHTML()
{
hide();
webViewInitialized = false;
jScriptInitialized = false;
gEarthInitialized = false;
show();
}
void QGCGoogleEarthView::enableEditMode(bool mode)
{
javaScript(QString("setDraggingAllowed(%1);").arg(mode));
}
void QGCGoogleEarthView::enableDaylight(bool enable)
{
javaScript(QString("enableDaylight(%1);").arg(enable));
}
void QGCGoogleEarthView::enableAtmosphere(bool enable)
{
javaScript(QString("enableAtmosphere(%1);").arg(enable));
}
/**
* @param range in meters (SI-units)
*/
void QGCGoogleEarthView::setViewRange(float range)
{
javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5));
}
void QGCGoogleEarthView::setDistanceMode(int mode)
{
javaScript(QString("setDistanceMode(%1);").arg(mode));
}
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));
}
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
// 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()));
// Automatically receive further position updates
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,double,quint64)));
// Receive waypoint updates
// Connect the waypoint manager / data storage to the UI
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*)));
// TODO Update waypoint list on UI changes here
}
void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
{
if (uas)
{
mav = uas;
javaScript(QString("setCurrAircraft(%1);").arg(uas->getUASID()));
updateWaypointList(uas->getUASID());
}
}
/**
* 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 || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
{
// We're good, this is a global waypoint
// Get the index of this waypoint
// note the call to getGlobalFrameAndNavTypeIndexOf()
// as we're only handling global waypoints
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameAndNavTypeIndexOf(wp);
// If not found, return (this should never happen, but helps safety)
if (wpindex == -1)
{
return;
}
else
{
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()));
//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());
}
}
}
/**
* 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
QList<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
// Trim internal list to number of global waypoints in the waypoint manager list
javaScript(QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count()));
qDebug() << QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count());
// Load all existing waypoints into map view
foreach (Waypoint* wp, wpList)
{
updateWaypoint(uas, wp);
}
}
}
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
Q_UNUSED(usec);
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));
}
void QGCGoogleEarthView::clearTrails()
{
QList<UASInterface*> mavs = UASManager::instance()->getUASList();
foreach (UASInterface* currMav, mavs)
{
javaScript(QString("clearTrail(%1);").arg(currMav->getUASID()));
}
}
void QGCGoogleEarthView::showTrail(bool state)
{
// 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;
ui->trailCheckbox->setChecked(state);
}
void QGCGoogleEarthView::showWaypoints(bool state)
{
waypointsEnabled = state;
}
void QGCGoogleEarthView::follow(bool follow)
{
ui->followAirplaneCheckbox->setChecked(follow);
if (follow != followCamera)
{
if (follow)
{
setViewMode(VIEW_MODE_CHASE_LOCKED);
}
else
{
setViewMode(VIEW_MODE_SIDE);
}
}
followCamera = follow;
javaScript(QString("setFollowEnabled(%1)").arg(follow));
}
void QGCGoogleEarthView::goHome()
{
// Disable follow and update
follow(false);
updateState();
// Go to home location
javaScript("goHome();");
}
void QGCGoogleEarthView::setHome(double lat, double lon, double alt)
{
qDebug() << "SETTING GCS HOME IN GOOGLE MAPS" << lat << lon << alt;
javaScript(QString("setGCSHome(%1,%2,%3);").arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
}
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));
}
}
}
}
void QGCGoogleEarthView::hideEvent(QHideEvent* event)
{
updateTimer->stop();
QWidget::hideEvent(event);
emit visibilityChanged(false);
}
void QGCGoogleEarthView::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
QWidget::showEvent(event);
// Enable widget, initialize on first run
if (!webViewInitialized)
{
#if (defined Q_OS_MAC)
webViewMac->setPage(new QGCWebPage(webViewMac));
webViewMac->settings()->setAttribute(QWebSettings::PluginsEnabled, true);
webViewMac->load(QUrl(QCoreApplication::applicationDirPath()+"/files/images/earth.html"));
#endif
#ifdef _MSC_VER
//webViewWin->dynamicCall("GoHome()");
webViewWin->dynamicCall("Navigate(const QString&)", QApplication::applicationDirPath() + "/files/images/earth.html");
#endif
webViewInitialized = true;
// Reloading the webpage, this resets Google Earth
gEarthInitialized = false;
QTimer::singleShot(3000, this, SLOT(initializeGoogleEarth()));
}
else
{
updateTimer->start(refreshRateMs);
}
emit visibilityChanged(true);
}
void QGCGoogleEarthView::printWinException(int no, QString str1, QString str2, QString str3)
{
qDebug() << no << str1 << str2 << str3;
}
QVariant QGCGoogleEarthView::javaScript(QString javaScript)
{
#ifdef Q_OS_MAC
if (!jScriptInitialized) {
return QVariant(false);
} else {
return webViewMac->page()->currentFrame()->evaluateJavaScript(javaScript);
}
#endif
#ifdef _MSC_VER
if(!jScriptInitialized) {
qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
return QVariant(false);
} else {
QVariantList params;
params.append(javaScript);
params.append("JScript");
QVariant result = jScriptWin->dynamicCall("execScript(QString, QString)", params);
return result;
}
#endif
}
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 {
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 (SUCCEEDED(res) && 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;
}
}
}
return QVariant(0);
#endif
}
void QGCGoogleEarthView::initializeGoogleEarth()
{
if (!jScriptInitialized) {
#ifdef Q_OS_MAC
jScriptInitialized = true;
#endif
#ifdef _MSC_VER
QAxObject* doc = webViewWin->querySubObject("Document()");
//IDispatch* Disp;
IDispatch* winDoc = NULL;
IHTMLDocument2* document = 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) {
document = NULL;
winDoc->QueryInterface( IID_IHTMLDocument2, (void**)&document );
IHTMLWindow2 *window = NULL;
document->get_parentWindow( &window );
documentWin = new QAxObject(document, webViewWin);
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";
}
#endif
QTimer::singleShot(1500, this, SLOT(initializeGoogleEarth()));
return;
}
if (!gEarthInitialized) {
if (!documentElement("initialized").toBool()) {
QTimer::singleShot(300, this, SLOT(initializeGoogleEarth()));
qDebug() << "NOT INITIALIZED, WAITING";
} else {
gEarthInitialized = true;
// Set home location
setHome(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
// Add all MAVs
QList<UASInterface*> mavs = UASManager::instance()->getUASList();
foreach (UASInterface* currMav, mavs) {
addUAS(currMav);
}
// Set current UAS
setActiveUAS(UASManager::instance()->getActiveUAS());
// Add any further MAV automatically
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
// Connect UI signals/slots
// Follow checkbox
ui->followAirplaneCheckbox->setChecked(followCamera);
connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool)), Qt::UniqueConnection);
// Trail checkbox
ui->trailCheckbox->setChecked(trailEnabled);
connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool)), Qt::UniqueConnection);
// Go home
connect(ui->goHomeButton, SIGNAL(clicked()), this, SLOT(goHome()));
// 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()));
// Cam distance slider
connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int)), Qt::UniqueConnection);
setViewRangeScaledInt(ui->camDistanceSlider->value());
// 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);
// Update waypoint list
if (mav) updateWaypointList(mav->getUASID());
// Start update timer
updateTimer->start(refreshRateMs);
// Set current view mode
setViewMode(currentViewMode);
setDistanceMode(ui->camDistanceComboBox->currentIndex());
enableEditMode(ui->editButton->isChecked());
enableAtmosphere(ui->atmosphereCheckBox->isChecked());
enableDaylight(ui->daylightCheckBox->isChecked());
follow(this->followCamera);
// Move to home location
goHome();
}
}
}
void QGCGoogleEarthView::updateState()
{
#if (QGC_EVENTLOOP_DEBUG)
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
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();
foreach (UASInterface* currMav, mavs)
{
// Only update if known
if (!currMav->globalPositionKnown()) continue;
uasId = currMav->getUASID();
lat = currMav->getLatitude();
lon = currMav->getLongitude();
alt = currMav->getAltitudeAMSL();
roll = currMav->getRoll();
pitch = currMav->getPitch();
yaw = currMav->getYaw();
//qDebug() << "SETTING POSITION FOR" << uasId << lat << lon << alt << roll << pitch << yaw;
javaScript(QString("setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);")
.arg(uasId)
.arg(lat, 0, 'f', 22)
.arg(lon, 0, 'f', 22)
.arg(alt, 0, 'f', 22)
.arg(roll, 0, 'f', 9)
.arg(pitch, 0, 'f', 9)
.arg(yaw, 0, 'f', 9));
}
// 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();
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)
{
Waypoint* wp = mav->getWaypointManager()->createWaypoint();
wp->setFrame(MAV_FRAME_GLOBAL);
wp->setAction(MAV_CMD_NAV_WAYPOINT);
wp->setLatitude(latitude);
wp->setLongitude(longitude);
wp->setAltitude(altitude);
wp->setAcceptanceRadius(10.0); // 10 m
}
}
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;
// UPDATE WAYPOINTS, HOME LOCATION AND OTHER LOCATIONS
if (coordsOk)
{
QString idText = documentElement("dragWaypointIndex").toString();
if (idText == "HOME")
{
qDebug() << "HOME UPDATED!";
UASManager::instance()->setHomePosition(latitude, longitude, altitude);
ui->setHomeButton->setChecked(false);
}
else
{
// Update waypoint or symbol
if (mav)
{
QList<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
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()->notifyOfChangeEditable(wp);
}
}
}
}
else
{
// If coords were not ok, move the view in google earth back
// to last acceptable location
updateWaypointList(mav->getUASID());
}
javaScript("setDragWaypointPending(false);");
}
}
}
void QGCGoogleEarthView::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);
switch (e->type()) {
case QEvent::LanguageChange:
ui->retranslateUi(this);
break;
default:
break;
}
}
#ifndef QGCGOOGLEEARTHVIEW_H
#define QGCGOOGLEEARTHVIEW_H
#include <QWidget>
#include <QTimer>
#include <UASInterface.h>
#if (defined Q_OS_MAC)
#include <QWebView>
#endif
#ifdef _MSC_VER
#include <ActiveQt/QAxWidget>
#include <ActiveQt/QAxObject>
#include "windows.h"
class QGCWebAxWidget : public QAxWidget
{
public:
//Q_OBJECT
QGCWebAxWidget(QWidget* parent = 0, Qt::WindowFlags f = 0)
: QAxWidget(parent, f)/*,
_document(NULL)*/
{
// Set web browser control
setControl("{8856F961-340A-11D0-A96B-00C04FD705A2}");
// WARNING: Makes it impossible to actually debug javascript. But useful in production mode
setProperty("ScriptErrorsSuppressed", true);
// see: http://www.codeproject.com/KB/cpp/ExtendedWebBrowser.aspx?fid=285594&df=90&mpp=25&noise=3&sort=Position&view=Quick&fr=151#GoalScriptError
//this->dynamicCall("setProperty(const QString&,
//QObject::connect(this, SIGNAL(DocumentComplete(IDispatch*, QVariant&)), this, SLOT(setDocument(IDispatch*, QVariant&)));
}
/*
QAxObject* document()
{
return _document;
}*/
protected:
/*
void setDocument(IDispatch* dispatch, QVariant& variant)
{
_document = this->querySubObject("Document()");
}
QAxObject* _document;*/
virtual bool translateKeyEvent(int message, int keycode) const {
if (message >= WM_KEYFIRST && message <= WM_KEYLAST)
return true;
else
return QAxWidget::translateKeyEvent(message, keycode);
}
};
#endif
namespace Ui
{
class QGCGoogleEarthView;
}
class Waypoint;
class QGCGoogleEarthView : public QWidget
{
Q_OBJECT
public:
explicit QGCGoogleEarthView(QWidget *parent = 0);
~QGCGoogleEarthView();
enum VIEW_MODE {
VIEW_MODE_SIDE = 0, ///< View from above, orientation is free
VIEW_MODE_MAP, ///< View from above, orientation is north (map view)
VIEW_MODE_CHASE_LOCKED, ///< Locked chase camera
VIEW_MODE_CHASE_FREE, ///< Position is chasing object, but view can rotate around object
};
public slots:
/** @brief Update the internal state. Does not trigger a redraw */
void updateState();
/** @brief Add a new MAV/UAS to the visualization */
void addUAS(UASInterface* uas);
/** @brief Set the currently selected UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Update the global position */
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
/** @brief Update a single waypoint */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief Update the waypoint list */
void updateWaypointList(int uas);
/** @brief Show the vehicle trail */
void showTrail(bool state);
/** @brief Clear the current vehicle trails and start with new ones */
void clearTrails();
/** @brief Show the waypoints */
void showWaypoints(bool state);
/** @brief Follow the aircraft during flight */
void follow(bool follow);
/** @brief Go to the home location */
void goHome();
/** @brief Set the home location */
void setHome(double lat, double lon, double alt);
/** @brief Set the home location interactively in the UI */
void setHome();
/** @brief Move the view to a latitude / longitude position */
void moveToPosition();
/** @brief Allow waypoint editing */
void enableEditMode(bool mode);
/** @brief Enable daylight/night */
void enableDaylight(bool enable);
/** @brief Enable atmosphere */
void enableAtmosphere(bool enable);
/** @brief Set camera view range to aircraft in meters */
void setViewRange(float range);
/** @brief Set the distance mode - either to ground or to MAV */
void setDistanceMode(int mode);
/** @brief Set the view mode */
void setViewMode(VIEW_MODE mode);
/** @brief Toggle through the different view modes */
void toggleViewMode();
/** @brief Set camera view range to aircraft in centimeters */
void setViewRangeScaledInt(int range);
/** @brief Reset Google Earth View */
void reloadHTML();
/** @brief Initialize Google Earth */
void initializeGoogleEarth();
/** @brief Print a Windows exception */
void printWinException(int no, QString str1, QString str2, QString str3);
public:
/** @brief Execute java script inside the Google Earth window */
QVariant javaScript(QString javascript);
/** @brief Get a document element */
QVariant documentElement(QString name);
signals:
void visibilityChanged(bool visible);
protected:
void changeEvent(QEvent *e);
QTimer* updateTimer;
int refreshRateMs;
UASInterface* mav;
bool followCamera;
bool trailEnabled;
bool waypointsEnabled;
bool webViewInitialized;
bool jScriptInitialized;
bool gEarthInitialized;
VIEW_MODE currentViewMode;
#ifdef _MSC_VER
QGCWebAxWidget* webViewWin;
QAxObject* jScriptWin;
QAxObject* documentWin;
#endif
#if (defined Q_OS_MAC)
QWebView* webViewMac;
#endif
/** @brief Start widget updating */
void showEvent(QShowEvent* event);
/** @brief Stop widget updating */
void hideEvent(QHideEvent* event);
private:
#ifdef _MSC_VER
Ui::QGCGoogleEarthView* ui;
#else
Ui::QGCGoogleEarthView* ui;
#endif
};
#endif // QGCGOOGLEEARTHVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCGoogleEarthView</class>
<widget class="QWidget" name="QGCGoogleEarthView">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1409</width>
<height>302</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="1,10,10,10,10,5,10,1000,10,10,10,10,10,5,2,2,0,0">
<property name="horizontalSpacing">
<number>4</number>
</property>
<property name="verticalSpacing">
<number>2</number>
</property>
<property name="margin">
<number>2</number>
</property>
<item row="0" column="0" colspan="18">
<layout class="QVBoxLayout" name="webViewLayout"/>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="goHomeButton">
<property name="toolTip">
<string>Go to home location</string>
</property>
<property name="statusTip">
<string>Go to home location</string>
</property>
<property name="whatsThis">
<string>Go to home location</string>
</property>
<property name="text">
<string>Home</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QPushButton" name="setHomeButton">
<property name="text">
<string>Set Home</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QPushButton" name="editButton">
<property name="toolTip">
<string>Enable waypoint and home location edit mode</string>
</property>
<property name="statusTip">
<string>Enable waypoint and home location edit mode</string>
</property>
<property name="text">
<string>Edit</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QCheckBox" name="trailCheckbox">
<property name="toolTip">
<string>Show MAV trajectories</string>
</property>
<property name="statusTip">
<string>Show MAV trajectories</string>
</property>
<property name="whatsThis">
<string>Show MAV trajectories</string>
</property>
<property name="text">
<string>Trails</string>
</property>
</widget>
</item>
<item row="1" column="5">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QComboBox" name="camDistanceComboBox">
<property name="toolTip">
<string>Select the MAV to chase</string>
</property>
<property name="statusTip">
<string>Select the MAV to chase</string>
</property>
<property name="whatsThis">
<string>Select the MAV to chase</string>
</property>
<item>
<property name="text">
<string>MAV Distance</string>
</property>
</item>
<item>
<property name="text">
<string>Ground Distance</string>
</property>
</item>
</widget>
</item>
<item row="1" column="7">
<widget class="QSlider" name="camDistanceSlider">
<property name="toolTip">
<string>Distance of the chase camera to the MAV</string>
</property>
<property name="statusTip">
<string>Distance of the chase camera to the MAV</string>
</property>
<property name="whatsThis">
<string>Distance of the chase camera to the MAV</string>
</property>
<property name="minimum">
<number>100</number>
</property>
<property name="maximum">
<number>20000</number>
</property>
<property name="value">
<number>3000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="8">
<widget class="QCheckBox" name="followAirplaneCheckbox">
<property name="toolTip">
<string>Chase the MAV</string>
</property>
<property name="statusTip">
<string>Chase the MAV</string>
</property>
<property name="whatsThis">
<string>Chase the MAV</string>
</property>
<property name="text">
<string>Follow</string>
</property>
</widget>
</item>
<item row="1" column="9">
<widget class="QPushButton" name="changeViewButton">
<property name="text">
<string>Overhead</string>
</property>
</widget>
</item>
<item row="1" column="10">
<widget class="Line" name="line_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item row="1" column="11">
<widget class="QPushButton" name="clearTrailsButton">
<property name="toolTip">
<string>Delete all waypoints</string>
</property>
<property name="statusTip">
<string>Delete all waypoints</string>
</property>
<property name="whatsThis">
<string>Delete all waypoints</string>
</property>
<property name="text">
<string>Clear Trails</string>
</property>
</widget>
</item>
<item row="1" column="12">
<widget class="QPushButton" name="resetButton">
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item row="1" column="13">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="14">
<widget class="QCheckBox" name="atmosphereCheckBox">
<property name="toolTip">
<string>Enable the atmosphere visualization. Not recommended for mission execution, only for visualization</string>
</property>
<property name="statusTip">
<string>Enable the atmosphere visualization. Not recommended for mission execution, only for visualization</string>
</property>
<property name="text">
<string>Sky</string>
</property>
</widget>
</item>
<item row="1" column="15">
<widget class="QCheckBox" name="daylightCheckBox">
<property name="toolTip">
<string>Enable day/night light. Not recommended for mission execution, only for visualization.</string>
</property>
<property name="statusTip">
<string>Enable day/night light. Not recommended for mission execution, only for visualization.</string>
</property>
<property name="text">
<string>Day/Night</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="toLatLonButton">
<property name="text">
<string>Lat/Lon</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment