Commit 6cd0d9f6 authored by LM's avatar LM

Fixed all known waypoint-editing related issues

parent dc3b21fb
......@@ -347,12 +347,12 @@ function updateWaypointListLength(id, len)
// Delete any non-needed waypoints
if (waypoints.length > len)
{
for (var i=len; i<waypoints.length; i++)
var initialLength = waypoints.length;
for (var i=len; i<initialLength; i++)
{
var placemark = waypoints.pop();
ge.getFeatures().removeChild(placemark);
var line = waypointLines[id].pop();
ge.getFeatures().removeChild(line);
waypointLines[id].getCoordinates().pop();
}
}
}
......@@ -478,11 +478,6 @@ function createWaypointLine(id, color)
lineStyle.setWidth(15);
waypointLineColors[id] = color;
lineStyle.getColor().set(color);  // aabbggrr format
// Add waypoint line
//waypointLines[id].setExtrude(false);
//waypointLines[id].setAltitudeMode(ge.ALTITUDE_ABSOLUTE);
......
......@@ -232,8 +232,8 @@ void Waypoint::setAcceptanceRadius(double radius)
void Waypoint::setParam1(double param1)
{
//qDebug() << "SENDER:" << QObject::sender();
//qDebug() << "PARAM1 SET REQ:" << param1;
//// // qDebug() << "SENDER:" << QObject::sender();
//// // qDebug() << "PARAM1 SET REQ:" << param1;
if (this->param1 != param1)
{
this->param1 = param1;
......
This diff is collapsed.
......@@ -108,13 +108,6 @@ public:
return this->uas; ///< Returns the owning UAS
}
// /** @name Global waypoint list operations */
// /*@{*/
// const QVector<Waypoint *> &getGlobalWaypointList(void) { return waypoints; } ///< Returns a const reference to the global waypoint list.
// void globalAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
// int globalRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
// /*@}*/
private:
/** @name Message send functions */
/*@{*/
......
......@@ -131,7 +131,6 @@ void WaypointList::setUAS(UASInterface* uas)
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
//connect(uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
//connect(uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
}
......
......@@ -18,7 +18,6 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
{
// Widget is inactive until shown
loadSettings(false);
// Set cache mode
}
QGCMapWidget::~QGCMapWidget()
......@@ -167,23 +166,22 @@ void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
/**
*
* @param uas the UAS/MAV to monitor/display with the HUD
* @param uas the UAS/MAV to monitor/display with the map widget
*/
void QGCMapWidget::addUAS(UASInterface* uas)
{
// // qDebug() << "ADDING UAS";
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
//connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)));
}
void QGCMapWidget::activeUASSet(UASInterface* uas)
{
// Only execute if proper UAS is set
if (!uas || !dynamic_cast<UASInterface*>(uas)) return;
if (!uas) return;
// Disconnect old MAV manager
if (currWPManager) {
if (currWPManager)
{
// Disconnect the waypoint manager / data storage from the UI
disconnect(currWPManager, SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int)));
disconnect(currWPManager, SIGNAL(waypointChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
......@@ -191,12 +189,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChange(Waypoint*)));
}
if (uas) {
if (uas)
{
currWPManager = uas->getWaypointManager();
// Delete all waypoints and add waypoint from new system
updateWaypointList(uas->getUASID());
// Connect the waypoint manager / data storage to the UI
connect(currWPManager, SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int)));
connect(currWPManager, SIGNAL(waypointChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
......@@ -204,6 +200,9 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChange(Waypoint*)));
updateSelectedSystem(uas->getUASID());
followUAVID = uas->getUASID();
// Delete all waypoints and add waypoint from new system
updateWaypointList(uas->getUASID());
}
}
......@@ -317,16 +316,19 @@ void QGCMapWidget::showGoToDialog()
QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
QString("%1,%2").arg(CurrentPosition().Lat(), 0, 'g', 6).arg(CurrentPosition().Lng(), 0, 'g', 6), &ok);
if (ok && !text.isEmpty()) {
if (ok && !text.isEmpty())
{
QStringList split = text.split(",");
if (split.length() == 2) {
if (split.length() == 2)
{
bool convert;
double latitude = split.first().toDouble(&convert);
ok &= convert;
double longitude = split.last().toDouble(&convert);
ok &= convert;
if (ok) {
if (ok)
{
internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude);
SetCurrentPosition(pos_lat_lon); // set the map position
}
......@@ -422,6 +424,7 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
*/
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
{
qDebug() << "UPDATING WP FUNCTION CALLED";
// Source of the event was in this widget, do nothing
if (firingWaypointChange == wp) return;
// Currently only accept waypoint updates from the UAS in focus
......@@ -443,6 +446,8 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
// Mark this wp as currently edited
firingWaypointChange = wp;
qDebug() << "UPDATING WAYPOINT" << wpindex << "IN 2D MAP";
// Check if wp exists yet in map
if (!waypointsToIcons.contains(wp))
{
......@@ -531,6 +536,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
*/
void QGCMapWidget::updateWaypointList(int uas)
{
qDebug() << "UPDATE WP LIST IN 2D MAP CALLED FOR UAS" << uas;
// Currently only accept waypoint updates from the UAS in focus
// this has to be changed to accept read-only updates from other systems as well.
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
......@@ -539,6 +545,8 @@ void QGCMapWidget::updateWaypointList(int uas)
// ORDER MATTERS HERE!
// TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
qDebug() << "DELETING NOW OLD WPS";
// Delete first all old waypoints
// this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
QVector<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
......@@ -564,6 +572,7 @@ void QGCMapWidget::updateWaypointList(int uas)
// Update all potentially new waypoints
foreach (Waypoint* wp, wps)
{
qDebug() << "UPDATING NEW WP" << wp->getId();
// Update / add only if new
if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
}
......
......@@ -217,7 +217,8 @@ void QGCGoogleEarthView::addUAS(UASInterface* uas)
void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
{
if (uas) {
if (uas)
{
mav = uas;
javaScript(QString("setCurrAircraft(%1);").arg(uas->getUASID()));
updateWaypointList(uas->getUASID());
......@@ -231,7 +232,8 @@ void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
{
// Only accept waypoints in global coordinate frame
if (wp->getFrame() == MAV_FRAME_GLOBAL && wp->isNavigationType()) {
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
......@@ -239,9 +241,12 @@ void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
// 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) {
if (wpindex == -1)
{
return;
} 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()));
//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());
}
......@@ -257,7 +262,8 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
{
// Get already existing waypoints
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if (uasInstance) {
if (uasInstance)
{
// Get all waypoints, including non-global waypoints
QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
......@@ -267,7 +273,8 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
qDebug() << QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count());
// Load all existing waypoints into map view
foreach (Waypoint* wp, wpList) {
foreach (Waypoint* wp, wpList)
{
updateWaypoint(uas, wp);
}
}
......@@ -284,7 +291,8 @@ void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, dou
void QGCGoogleEarthView::clearTrails()
{
QList<UASInterface*> mavs = UASManager::instance()->getUASList();
foreach (UASInterface* currMav, mavs) {
foreach (UASInterface* currMav, mavs)
{
javaScript(QString("clearTrail(%1);").arg(currMav->getUASID()));
}
}
......@@ -292,9 +300,11 @@ void QGCGoogleEarthView::clearTrails()
void QGCGoogleEarthView::showTrail(bool state)
{
// Check if the current trail has to be hidden
if (trailEnabled && !state) {
if (trailEnabled && !state)
{
QList<UASInterface*> mavs = UASManager::instance()->getUASList();
foreach (UASInterface* currMav, mavs) {
foreach (UASInterface* currMav, mavs)
{
javaScript(QString("hideTrail(%1);").arg(currMav->getUASID()));
}
}
......
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