Commit ca6f3518 authored by pixhawk's avatar pixhawk

Added initial waypoint support

parent fe401d20
...@@ -53,6 +53,8 @@ var trails = []; ...@@ -53,6 +53,8 @@ var trails = [];
var trailPlacemarks = []; var trailPlacemarks = [];
var trailsVisible = []; var trailsVisible = [];
var trailColors = []; var trailColors = [];
var waypoints = [];
//var waypointLines = [];
//var trailPlacemarks[id]; //var trailPlacemarks[id];
var lineStyle; var lineStyle;
...@@ -116,6 +118,60 @@ function setGCSHome(lat, lon, alt) ...@@ -116,6 +118,60 @@ function setGCSHome(lat, lon, alt)
} }
} }
function updateWaypointListLength(id, len)
{
// Delete any non-needed waypoints
if (waypoints.length > len)
{
for (var i=len; i<waypoints.length; i++)
{
var placemark = waypoints.pop();
ge.getFeatures().removeChild(placemark);
}
}
}
function updateWaypoint(id, index, lat, lon, alt, action)
{
// Check if waypoint exists
if (waypoints.length > index)
{
// Waypoint exists
// Set the placemark's location.
var location = ge.createPoint('');
location.setLatitude(lat);
location.setLongitude(lon);
location.setAltitude(alt);
waypoints[index].setGeometry(location);
}
else
{
// Waypoint does not exist yet
var placemark = ge.createPlacemark('');
var icon = ge.createIcon('');
var numberstring = index;
if (index < 10) numberstring = '0' + numberstring
icon.setHref('http://google-maps-icons.googlecode.com/files/red' + numberstring +'.png');
var style = ge.createStyle('');
style.getIconStyle().setIcon(icon);
//style.getIconStyle().setScale(0.5);
placemark.setStyleSelector(style);
// Set the placemark's location.
var location = ge.createPoint('');
location.setLatitude(lat);
location.setLongitude(lon);
location.setAltitude(alt);
placemark.setGeometry(location);
// Add the placemark to Earth.
ge.getFeatures().appendChild(placemark);
waypoints[index] = placemark;
}
// Add connecting line
}
function createAircraft(id, type, color) function createAircraft(id, type, color)
{ {
planePlacemark = ge.createPlacemark(''); planePlacemark = ge.createPlacemark('');
......
...@@ -23,6 +23,7 @@ ...@@ -23,6 +23,7 @@
#include "QGC.h" #include "QGC.h"
#include "ui_QGCGoogleEarthView.h" #include "ui_QGCGoogleEarthView.h"
#include "QGCGoogleEarthView.h" #include "QGCGoogleEarthView.h"
#include "UASWaypointManager.h"
#define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_") #define QGCGOOGLEEARTHVIEWSETTINGS QString("GoogleEarthViewSettings_")
...@@ -82,6 +83,7 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) : ...@@ -82,6 +83,7 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
#endif #endif
connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState())); connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateState()));
connect(ui->resetButton, SIGNAL(clicked()), this, SLOT(reloadHTML()));
} }
QGCGoogleEarthView::~QGCGoogleEarthView() QGCGoogleEarthView::~QGCGoogleEarthView()
...@@ -107,6 +109,15 @@ void QGCGoogleEarthView::setViewRangeScaledInt(int range) ...@@ -107,6 +109,15 @@ void QGCGoogleEarthView::setViewRangeScaledInt(int range)
setViewRange(range/100.0f); setViewRange(range/100.0f);
} }
void QGCGoogleEarthView::reloadHTML()
{
hide();
webViewInitialized = false;
jScriptInitialized = false;
gEarthInitialized = false;
show();
}
/** /**
* @param range in meters (SI-units) * @param range in meters (SI-units)
*/ */
...@@ -129,9 +140,14 @@ void QGCGoogleEarthView::addUAS(UASInterface* uas) ...@@ -129,9 +140,14 @@ void QGCGoogleEarthView::addUAS(UASInterface* uas)
if (trailEnabled) javaScript(QString("showTrail(%1);").arg(uas->getUASID())); if (trailEnabled) javaScript(QString("showTrail(%1);").arg(uas->getUASID()));
//javaScript(QString("createAircraft(%1, %2, %3);").arg(uas->getUASID()).arg(uas->getSystemType()).arg("0"));
// Automatically receive further position updates // Automatically receive further position updates
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
// 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
} }
void QGCGoogleEarthView::setActiveUAS(UASInterface* uas) void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
...@@ -143,6 +159,70 @@ void QGCGoogleEarthView::setActiveUAS(UASInterface* uas) ...@@ -143,6 +159,70 @@ void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
} }
} }
/**
* 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
{
javaScript(QString("updateWaypoint(%1,%2,%3,%4,%5,%6);").arg(uas).arg(wpindex).arg(wp->getY()).arg(wp->getX()).arg(wp->getZ()).arg(wp->getAction()));
}
}
else
{
// Check if the index of this waypoint is larger than the global
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
// if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameCount())
// {
// updateWaypointList(uas);
// }
}
}
/**
* 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()));
// Load all existing waypoints into map view
foreach (Waypoint* wp, wpList)
{
updateWaypoint(uas, wp);
}
}
}
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec) void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
{ {
Q_UNUSED(usec); Q_UNUSED(usec);
......
...@@ -58,13 +58,11 @@ protected: ...@@ -58,13 +58,11 @@ protected:
#endif #endif
namespace Ui { namespace Ui {
#ifdef _MSC_VER
class QGCGoogleEarthView;
#else
class QGCGoogleEarthView; class QGCGoogleEarthView;
#endif
} }
class Waypoint;
class QGCGoogleEarthView : public QWidget class QGCGoogleEarthView : public QWidget
{ {
Q_OBJECT Q_OBJECT
...@@ -82,6 +80,10 @@ public slots: ...@@ -82,6 +80,10 @@ public slots:
void setActiveUAS(UASInterface* uas); void setActiveUAS(UASInterface* uas);
/** @brief Update the global position */ /** @brief Update the global position */
void updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec); void updateGlobalPosition(UASInterface* uas, double lon, double lat, 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 */ /** @brief Show the vehicle trail */
void showTrail(bool state); void showTrail(bool state);
/** @brief Show the waypoints */ /** @brief Show the waypoints */
...@@ -96,6 +98,8 @@ public slots: ...@@ -96,6 +98,8 @@ public slots:
void setViewRange(float range); void setViewRange(float range);
/** @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 */
void reloadHTML();
/** @brief Initialize Google Earth */ /** @brief Initialize Google Earth */
void initializeGoogleEarth(); void initializeGoogleEarth();
......
...@@ -23,7 +23,7 @@ ...@@ -23,7 +23,7 @@
<property name="margin"> <property name="margin">
<number>2</number> <number>2</number>
</property> </property>
<item row="0" column="0" colspan="12"> <item row="0" column="0" colspan="13">
<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 @@ ...@@ -58,7 +58,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="11"> <item row="1" column="12">
<spacer name="horizontalSpacer"> <spacer name="horizontalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
...@@ -180,6 +180,13 @@ ...@@ -180,6 +180,13 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="11">
<widget class="QPushButton" name="resetButton">
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
<resources/> <resources/>
......
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