Browse Source

Fixed initialization of Google Earth, works now flawlessly. Further improvements needed on simulation link and Google Earth JavaScript.

QGC4.4
lm 15 years ago
parent
commit
14609cb829
  1. 5
      images/earth.html
  2. 2
      src/comm/MAVLinkSimulationLink.cc
  3. 43
      src/ui/map3D/QGCGoogleEarthView.cc

5
images/earth.html

@ -27,7 +27,7 @@ var homeViewRange = 500; @@ -27,7 +27,7 @@ var homeViewRange = 500;
var homeLocation = null;
var homeGroundLevel = 0;
var currViewRange = 3.0; ///<< The current viewing range from this position (in meters)
var currViewRange = 50.0; ///<< The current viewing range from this position (in meters)
var currTilt = 40.0; ///<< The tilt angle (in degrees)
var currFollowTilt = 40.0;
var currView = null;
@ -183,7 +183,8 @@ function initCallback(object) @@ -183,7 +183,8 @@ function initCallback(object)
ge.getWindow().setVisibility(true);
ge.getOptions().setStatusBarVisibility(true);
ge.getOptions().setScaleLegendVisibility(true);
ge.getOptions().setFlyToSpeed(ge.SPEED_TELEPORT);
ge.getOptions().setFlyToSpeed(5.0);
//ge.getOptions().setFlyToSpeed(ge.SPEED_TELEPORT);
ge.getNavigationControl().setVisibility(ge.VISIBILITY_AUTO);
ge.getLayerRoot().enableLayerById(ge.LAYER_TERRAIN, true);

2
src/comm/MAVLinkSimulationLink.cc

@ -413,7 +413,7 @@ void MAVLinkSimulationLink::mainloop() @@ -413,7 +413,7 @@ void MAVLinkSimulationLink::mainloop()
// streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 47.378028137103+(x*0.002), 8.54899892510421+(y*0.002), z+35.0, 0, 0, 0);
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 47.378028137103+(x*0.0005), 8.54899892510421+(y*0.0005), z+35.0, 0, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);

43
src/ui/map3D/QGCGoogleEarthView.cc

@ -29,7 +29,7 @@ @@ -29,7 +29,7 @@
QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
QWidget(parent),
updateTimer(new QTimer(this)),
refreshRateMs(80),
refreshRateMs(60),
mav(NULL),
followCamera(true),
trailEnabled(true),
@ -108,7 +108,8 @@ QGCGoogleEarthView::~QGCGoogleEarthView() @@ -108,7 +108,8 @@ QGCGoogleEarthView::~QGCGoogleEarthView()
void QGCGoogleEarthView::addUAS(UASInterface* uas)
{
// uasid, type, color (in aarrbbgg format)
javaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg(uas->getColor().name().remove(0, 1).prepend("50")));
//javaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg(uas->getColor().name().remove(0, 1).prepend("50")));
javaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg("0"));
// Automatically receive further position updates
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
}
@ -189,7 +190,7 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event) @@ -189,7 +190,7 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event)
// Reloading the webpage, this resets Google Earth
gEarthInitialized = false;
QTimer::singleShot(1000, this, SLOT(initializeGoogleEarth()));
QTimer::singleShot(2000, this, SLOT(initializeGoogleEarth()));
updateTimer->start(refreshRateMs);
}
}
@ -208,8 +209,7 @@ QVariant QGCGoogleEarthView::javaScript(QString javaScript) @@ -208,8 +209,7 @@ QVariant QGCGoogleEarthView::javaScript(QString javaScript)
#ifdef _MSC_VER
if(!jScriptInitialized)
{
// Inititalize and drop call
initializeGoogleEarth();
qDebug() << "TOO EARLY JAVASCRIPT CALL, ABORTING";
return QVariant(false);
}
else
@ -224,22 +224,13 @@ QVariant QGCGoogleEarthView::javaScript(QString javaScript) @@ -224,22 +224,13 @@ QVariant QGCGoogleEarthView::javaScript(QString javaScript)
void QGCGoogleEarthView::initializeGoogleEarth()
{
if (!gEarthInitialized)
{
#ifdef Q_OS_MAC
if (!webViewMac->page()->currentFrame()->evaluateJavaScript("isInitialized();").toBool())
{
if (!jScriptInitialized)
{
#ifdef Q_OS_MAC
jScriptInitialized = true;
#endif
#ifdef _MSC_VER
static bool first = true;
if (first)
{
QTimer::singleShot(500, this, SLOT(initializeGoogleEarth()));
first = false;
}
else
{
QAxObject* doc = webViewWin->querySubObject("Document()");
#ifdef _MSC_VER
QAxObject* doc = webViewWin->querySubObject("Document()");
IDispatch* Disp;
IDispatch* winDoc = NULL;
@ -266,7 +257,19 @@ void QGCGoogleEarthView::initializeGoogleEarth() @@ -266,7 +257,19 @@ void QGCGoogleEarthView::initializeGoogleEarth()
qDebug() << "COULD NOT GET DOCUMENT OBJECT! Aborting";
}
#endif
QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth()));
return;
}
if (!gEarthInitialized)
{
if (0 == 1)//(!javaScript("isInitialized();").toBool())
{
QTimer::singleShot(500, this, SLOT(initializeGoogleEarth()));
qDebug() << "NOT INITIALIZED, WAITING";
}
else
{
// Set home location
setHome(47.3769, 8.549444, 500);

Loading…
Cancel
Save