Commit 50f933d3 authored by lm's avatar lm

Fixed waypoint reading

parent 39468055
......@@ -575,7 +575,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
float x = static_cast<double>(pos.lat)/1E7;
float y = static_cast<double>(pos.lon)/1E7;
float z = static_cast<double>(pos.alt)/1000;
//float z = static_cast<double>(pos.alt)/1000;
//qDebug() << "Received new position: x:" << x << "| y:" << y << "| z:" << z;
......
......@@ -276,49 +276,113 @@ void WaypointList::waypointListChanged()
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
// Get all waypoints
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
// Store the current state, then check which widgets to update
// and which ones to delete
QList<Waypoint*> oldWaypoints = wpViews.keys();
foreach (Waypoint* wp, waypoints)
{
// Create any new waypoint
if (!wpViews.contains(wp))
if (!wpViews.empty())
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
viewIt.toFront();
while(viewIt.hasNext())
{
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
}
}
else
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
// Update existing waypoints
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
// Mark as updated by removing from old list
oldWaypoints.removeAt(oldWaypoints.indexOf(wp));
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
this->setUpdatesEnabled(true);
}
// The old list now contains all wps to be deleted
foreach (Waypoint* wp, oldWaypoints)
{
// Delete waypoint view and entry in list
WaypointView* wpv = wpViews.value(wp);
if (wpv)
{
wpv->deleteLater();
}
wpViews.remove(wp);
}
loadFileGlobalWP = false;
}
//void WaypointList::waypointListChanged()
//{
// if (uas)
// {
// // Prevent updates to prevent visual flicker
// this->setUpdatesEnabled(false);
// // Get all waypoints
// const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
//// // Store the current state, then check which widgets to update
//// // and which ones to delete
//// QList<Waypoint*> oldWaypoints = wpViews.keys();
//// foreach (Waypoint* wp, waypoints)
//// {
//// WaypointView* wpview;
//// // Create any new waypoint
//// if (!wpViews.contains(wp))
//// {
//// wpview = new WaypointView(wp, this);
//// wpViews.insert(wp, wpview);
//// connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
//// connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
//// connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
//// connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
//// connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
//// listLayout->addWidget(wpview);
//// }
//// else
//// {
//// // Update existing waypoints
//// wpview = wpViews.value(wp);
//// }
//// // Mark as updated by removing from old list
//// oldWaypoints.removeAt(oldWaypoints.indexOf(wp));
//// wpview->updateValues(); // update the values of the ui elements in the view
//// }
//// // The old list now contains all wps to be deleted
//// foreach (Waypoint* wp, oldWaypoints)
//// {
//// // Delete waypoint view and entry in list
//// WaypointView* wpv = wpViews.value(wp);
//// if (wpv)
//// {
//// listLayout->removeWidget(wpv);
//// delete wpv;
//// }
//// wpViews.remove(wp);
//// }
// if (!wpViews.empty())
// {
......@@ -339,8 +403,11 @@ void WaypointList::waypointListChanged()
// if (i == waypoints.size())
// {
// WaypointView* widget = wpViews.find(cur).value();
// widget->hide();
// listLayout->removeWidget(widget);
// if (widget)
// {
// widget->hide();
// listLayout->removeWidget(widget);
// }
// wpViews.remove(cur);
// }
// }
......@@ -365,10 +432,10 @@ void WaypointList::waypointListChanged()
// listLayout->addWidget(wpv);
// }
this->setUpdatesEnabled(true);
}
loadFileGlobalWP = false;
}
// this->setUpdatesEnabled(true);
// }
//// loadFileGlobalWP = false;
//}
void WaypointList::moveUp(Waypoint* wp)
{
......
......@@ -334,10 +334,10 @@ void WaypointView::updateFrameView(int frame)
void WaypointView::deleted(QObject* waypoint)
{
if (waypoint == this->wp)
{
deleteLater();
}
// if (waypoint == this->wp)
// {
// deleteLater();
// }
}
void WaypointView::changedFrame(int index)
......
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