Browse Source

Fully working drag and drop for Google Earth

QGC4.4
lm 14 years ago
parent
commit
6c5ff74565
  1. 32
      images/earth.html
  2. 2
      src/uas/UAS.cc
  3. 2
      src/ui/QGCParamWidget.cc
  4. 2
      src/ui/WaypointView.ui
  5. 47
      src/ui/map3D/QGCGoogleEarthView.cc
  6. 13
      src/ui/map3D/QGCGoogleEarthView.h
  7. 13
      src/ui/map3D/QGCGoogleEarthView.ui

32
images/earth.html

@ -37,6 +37,11 @@ var currTilt = 40.0; ///<< The tilt angle (in degrees)
var currFollowTilt = 40.0; var currFollowTilt = 40.0;
var currView = null; var currView = null;
var viewMode = 0;
var lastTilt = 0;
var lastRoll = 0;
var lastHeading = 0;
var M_PI = 3.14159265; var M_PI = 3.14159265;
@ -486,11 +491,34 @@ function setCurrentAircraft(id)
/** @brief Set the current view mode /** @brief Set the current view mode
* *
* @param mode 0: map view, 1: chase cam, fixed, 2: chase cam, free * @param mode 0: side map view, 1: top/north map view, 2: fixed chase cam, 3: free chase cam
*/ */
function setViewMode(mode) function setViewMode(mode)
{ {
viewMode = mode;
var currView = ge.getView().copyAsLookAt(ge.ALTITUDE_ABSOLUTE);
if (mode == 0)
{
currView.setTilt(0);
currView.setHeading(0);
}
if (mode == 1)
{
lastTilt = currView.getTilt();
lastHeading = currView.getHeading();
var lastLat2 = currView.getLatitude();
var lastLon2 = currView.getLongitude();
var lastAlt2 = currView.getAltitude();
currView.setTilt(0);
currView.setHeading(0);
currView.setLatitude(lastLat2);
currView.setLongitude(lastLon2);
currView.setAltitude(lastAlt2);
}
ge.getView().setAbstractView(currView);
} }
function updateFollowAircraft() function updateFollowAircraft()

2
src/uas/UAS.cc

@ -661,7 +661,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
alt = 0; alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE"); emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
} }
emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E7, time); emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
// Smaller than threshold and not NaN // Smaller than threshold and not NaN
if (pos.v < 1000000 && pos.v == pos.v) if (pos.v < 1000000 && pos.v == pos.v)
{ {

2
src/ui/QGCParamWidget.cc

@ -258,7 +258,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
bool justWritten = false; bool justWritten = false;
bool writeMismatch = false; bool writeMismatch = false;
bool lastWritten = false; //bool lastWritten = false;
// Mark this parameter as received in write ACK list // Mark this parameter as received in write ACK list
QMap<QString, float>* map = transmissionMissingWriteAckPackets.value(component); QMap<QString, float>* map = transmissionMissingWriteAckPackets.value(component);
if (map && map->contains(parameterName)) if (map && map->contains(parameterName))

2
src/ui/WaypointView.ui

@ -161,7 +161,7 @@ QProgressBar::chunk#thrustBar {
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="1,1,2,2,10,10,10,10,10,10,10,10,10,10,10,10,10,1,1,1,1"> <layout class="QHBoxLayout" name="horizontalLayout" stretch="1,1,2,3,10,10,10,10,10,10,10,10,10,10,10,10,10,1,1,1,1">
<property name="spacing"> <property name="spacing">
<number>2</number> <number>2</number>
</property> </property>

47
src/ui/map3D/QGCGoogleEarthView.cc

@ -38,6 +38,7 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
webViewInitialized(false), webViewInitialized(false),
jScriptInitialized(false), jScriptInitialized(false),
gEarthInitialized(false), gEarthInitialized(false),
currentViewMode(QGCGoogleEarthView::VIEW_MODE_SIDE),
#if (defined Q_OS_MAC) #if (defined Q_OS_MAC)
webViewMac(new QWebView(this)), webViewMac(new QWebView(this)),
#endif #endif
@ -85,6 +86,7 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState())); connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState()));
connect(ui->resetButton, SIGNAL(clicked()), this, SLOT(reloadHTML())); connect(ui->resetButton, SIGNAL(clicked()), this, SLOT(reloadHTML()));
connect(ui->changeViewButton, SIGNAL(clicked()), this, SLOT(toggleViewMode()));
} }
QGCGoogleEarthView::~QGCGoogleEarthView() QGCGoogleEarthView::~QGCGoogleEarthView()
@ -127,6 +129,46 @@ void QGCGoogleEarthView::setViewRange(float range)
javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5)); javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5));
} }
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) void QGCGoogleEarthView::addUAS(UASInterface* uas)
{ {
// uasid, type, color (in #rrbbgg format) // uasid, type, color (in #rrbbgg format)
@ -183,7 +225,7 @@ void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
else else
{ {
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())); 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()); //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());
} }
} }
} }
@ -453,6 +495,9 @@ void QGCGoogleEarthView::initializeGoogleEarth()
// Start update timer // Start update timer
updateTimer->start(refreshRateMs); updateTimer->start(refreshRateMs);
// Set current view mode
setViewMode(currentViewMode);
follow(this->followCamera); follow(this->followCamera);
gEarthInitialized = true; gEarthInitialized = true;

13
src/ui/map3D/QGCGoogleEarthView.h

@ -71,6 +71,14 @@ public:
explicit QGCGoogleEarthView(QWidget *parent = 0); explicit QGCGoogleEarthView(QWidget *parent = 0);
~QGCGoogleEarthView(); ~QGCGoogleEarthView();
enum VIEW_MODE
{
VIEW_MODE_SIDE, ///< 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: public slots:
/** @brief Update the internal state. Does not trigger a redraw */ /** @brief Update the internal state. Does not trigger a redraw */
void updateState(); void updateState();
@ -96,6 +104,10 @@ public slots:
void setHome(double lat, double lon, double alt); void setHome(double lat, double lon, double alt);
/** @brief Set camera view range to aircraft in meters */ /** @brief Set camera view range to aircraft in meters */
void setViewRange(float range); void setViewRange(float range);
/** @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 */ /** @brief Set camera view range to aircraft in centimeters */
void setViewRangeScaledInt(int range); void setViewRangeScaledInt(int range);
/** @brief Reset Google Earth View */ /** @brief Reset Google Earth View */
@ -123,6 +135,7 @@ protected:
bool webViewInitialized; bool webViewInitialized;
bool jScriptInitialized; bool jScriptInitialized;
bool gEarthInitialized; bool gEarthInitialized;
VIEW_MODE currentViewMode;
#ifdef _MSC_VER #ifdef _MSC_VER
QGCWebAxWidget* webViewWin; QGCWebAxWidget* webViewWin;
QAxObject* jScriptWin; QAxObject* jScriptWin;

13
src/ui/map3D/QGCGoogleEarthView.ui

@ -23,7 +23,7 @@
<property name="margin"> <property name="margin">
<number>2</number> <number>2</number>
</property> </property>
<item row="0" column="0" colspan="13"> <item row="0" column="0" colspan="14">
<layout class="QVBoxLayout" name="webViewLayout"/> <layout class="QVBoxLayout" name="webViewLayout"/>
</item> </item>
<item row="1" column="1"> <item row="1" column="1">
@ -58,7 +58,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="12"> <item row="1" column="13">
<spacer name="horizontalSpacer"> <spacer name="horizontalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -180,13 +180,20 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="11"> <item row="1" column="12">
<widget class="QPushButton" name="resetButton"> <widget class="QPushButton" name="resetButton">
<property name="text"> <property name="text">
<string>Reset</string> <string>Reset</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="11">
<widget class="QPushButton" name="changeViewButton">
<property name="text">
<string>Overhead</string>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
<resources/> <resources/>

Loading…
Cancel
Save