Commit ea098a0d authored by pixhawk's avatar pixhawk

Added a lot of "

view only" functions and renamed some of the old functions. This version compiles, but has a lot of bugs.
parent 26fc0ce0
......@@ -46,7 +46,7 @@ UASWaypointManager::UASWaypointManager(UAS &_uas)
current_partner_systemid(0),
current_partner_compid(0),
protocol_timer(this),
currentWaypoint(NULL)
currentWaypointEditable(NULL)
{
connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
connect(&uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
......@@ -92,11 +92,11 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x,
{
Q_UNUSED(mav);
Q_UNUSED(time);
if (waypoints.count() > 0 && currentWaypoint && (currentWaypoint->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypoint->getFrame() == MAV_FRAME_LOCAL_ENU))
if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU))
{
double xdiff = x-currentWaypoint->getX();
double ydiff = y-currentWaypoint->getY();
double zdiff = z-currentWaypoint->getZ();
double xdiff = x-currentWaypointEditable->getX();
double ydiff = y-currentWaypointEditable->getY();
double zdiff = z-currentWaypointEditable->getZ();
double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
emit waypointDistanceChanged(dist);
}
......@@ -144,9 +144,17 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id) {
//// // qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << "Frame:"<< (MAV_FRAME) wp->frame << "Command:" << (MAV_CMD) wp->command;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypointEditable(lwp, false);
if (wp->current == 1) currentWaypoint = lwp;
Waypoint *lwp_vo = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypointViewOnly(lwp_vo);
if (read_to_edit == true) {
Waypoint *lwp_ed = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypointEditable(lwp_ed, false);
if (wp->current == 1) currentWaypointEditable = lwp_ed;
}
//get next waypoint
current_wp_id++;
......@@ -165,7 +173,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
protocol_timer.stop();
emit readGlobalWPFromUAS(false);
if (currentWaypoint) emit currentWaypointChanged(currentWaypoint->getId());
if (currentWaypointEditable) emit currentWaypointChanged(currentWaypointEditable->getId());
emit updateStatusString("done.");
// // qDebug() << "got all waypoints from ID " << systemId;
......@@ -230,14 +238,13 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
current_state = WP_IDLE;
// update the local main storage
if (wpc->seq < waypoints.size()) {
for(int i = 0; i < waypoints.size(); i++) {
if (waypoints[i]->getId() == wpc->seq) {
waypoints[i]->setCurrent(true);
currentWaypoint = waypoints[i];
if (wpc->seq < waypointsViewOnly.size()) {
for(int i = 0; i < waypointsViewOnly.size(); i++) {
if (waypointsViewOnly[i]->getId() == wpc->seq) {
waypointsViewOnly[i]->setCurrent(true);
//currentWaypointEditable = waypoints[i];
} else {
waypoints[i]->setCurrent(false);
waypointsViewOnly[i]->setCurrent(false);
}
}
}
......@@ -268,15 +275,15 @@ void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
{
if (seq < waypoints.size()) {
if (seq < waypointsViewOnly.size()) {
if(current_state == WP_IDLE) {
//update local main storage
for(int i = 0; i < waypoints.size(); i++) {
if (waypoints[i]->getId() == seq) {
waypoints[i]->setCurrent(true);
currentWaypoint = waypoints[i];
for(int i = 0; i < waypointsViewOnly.size(); i++) {
if (waypointsViewOnly[i]->getId() == seq) {
waypointsViewOnly[i]->setCurrent(true);
//currentWaypointEditable = waypoints[i];
} else {
waypoints[i]->setCurrent(false);
waypointsViewOnly[i]->setCurrent(false);
}
}
......@@ -301,6 +308,26 @@ int UASWaypointManager::setCurrentWaypoint(quint16 seq)
return -1;
}
void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
if (wp)
{
wp->setId(waypointsViewOnly.size());
if (waypointsEditable.size() == 0)
{
wp->setCurrent(true);
//currentWaypointEditable = wp;
}
waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));
emit waypointViewOnlyListChanged();
emit waypointViewOnlyListChanged(uas.getUASID());
}
}
/**
* @warning Make sure the waypoint stays valid for the whole application lifecycle!
* @param enforceFirstActive Enforces that the first waypoint is set as active
......@@ -310,13 +337,13 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi
{
if (wp)
{
wp->setId(waypoints.size());
if (enforceFirstActive && waypoints.size() == 0)
wp->setId(waypointsEditable.size());
if (enforceFirstActive && waypointsEditable.size() == 0)
{
wp->setCurrent(true);
currentWaypoint = wp;
currentWaypointEditable = wp;
}
waypoints.insert(waypoints.size(), wp);
waypointsEditable.insert(waypointsEditable.size(), wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
emit waypointEditableListChanged();
......@@ -330,13 +357,13 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
Waypoint* wp = new Waypoint();
wp->setId(waypoints.size());
if (enforceFirstActive && waypoints.size() == 0)
wp->setId(waypointsEditable.size());
if (enforceFirstActive && waypointsEditable.size() == 0)
{
wp->setCurrent(true);
currentWaypoint = wp;
currentWaypointEditable = wp;
}
waypoints.insert(waypoints.size(), wp);
waypointsEditable.insert(waypointsEditable.size(), wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
emit waypointEditableListChanged();
......@@ -346,16 +373,16 @@ Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
int UASWaypointManager::removeWaypoint(quint16 seq)
{
if (seq < waypoints.size())
if (seq < waypointsEditable.size())
{
Waypoint *t = waypoints[seq];
waypoints.remove(seq);
Waypoint *t = waypointsEditable[seq];
waypointsEditable.remove(seq);
delete t;
t = NULL;
for(int i = seq; i < waypoints.size(); i++)
for(int i = seq; i < waypointsEditable.size(); i++)
{
waypoints[i]->setId(i);
waypointsEditable[i]->setId(i);
}
emit waypointEditableListChanged();
......@@ -367,23 +394,23 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
{
if (cur_seq != new_seq && cur_seq < waypoints.size() && new_seq < waypoints.size())
if (cur_seq != new_seq && cur_seq < waypointsEditable.size() && new_seq < waypointsEditable.size())
{
Waypoint *t = waypoints[cur_seq];
Waypoint *t = waypointsEditable[cur_seq];
if (cur_seq < new_seq) {
for (int i = cur_seq; i < new_seq; i++)
{
waypoints[i] = waypoints[i+1];
waypointsEditable[i] = waypointsEditable[i+1];
}
}
else
{
for (int i = cur_seq; i > new_seq; i--)
{
waypoints[i] = waypoints[i-1];
waypointsEditable[i] = waypointsEditable[i-1];
}
}
waypoints[new_seq] = t;
waypointsEditable[new_seq] = t;
emit waypointEditableListChanged();
emit waypointEditableListChanged(uas.getUASID());
......@@ -401,10 +428,10 @@ void UASWaypointManager::saveWaypoints(const QString &saveFile)
//write the waypoint list version to the first line for compatibility check
out << "QGC WPL 110\r\n";
for (int i = 0; i < waypoints.size(); i++)
for (int i = 0; i < waypointsEditable.size(); i++)
{
waypoints[i]->setId(i);
waypoints[i]->save(out);
waypointsEditable[i]->setId(i);
waypointsEditable[i]->save(out);
}
file.close();
}
......@@ -415,9 +442,9 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
return;
while(waypoints.size()>0) {
Waypoint *t = waypoints[0];
waypoints.remove(0);
while(waypointsEditable.size()>0) {
Waypoint *t = waypointsEditable[0];
waypointsEditable.remove(0);
delete t;
}
......@@ -436,8 +463,8 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
Waypoint *t = new Waypoint();
if(t->load(in))
{
t->setId(waypoints.size());
waypoints.insert(waypoints.size(), t);
t->setId(waypointsEditable.size());
waypointsEditable.insert(waypointsEditable.size(), t);
}
else
{
......@@ -477,7 +504,7 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
foreach (Waypoint* wp, waypoints)
foreach (Waypoint* wp, waypointsEditable)
{
if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
......@@ -493,7 +520,7 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointLi
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
foreach (Waypoint* wp, waypoints)
foreach (Waypoint* wp, waypointsEditable)
{
if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
{
......@@ -509,7 +536,7 @@ const QVector<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
foreach (Waypoint* wp, waypoints)
foreach (Waypoint* wp, waypointsEditable)
{
if (wp->isNavigationType())
{
......@@ -521,15 +548,15 @@ const QVector<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
return waypoints.indexOf(wp);
return waypointsEditable.indexOf(wp);
}
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints) {
foreach (Waypoint* p, waypointsEditable) {
if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
if (p == wp)
......@@ -545,10 +572,10 @@ int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp)
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints) {
foreach (Waypoint* p, waypointsEditable) {
if ((p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
{
if (p == wp)
......@@ -564,10 +591,10 @@ int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp)
int UASWaypointManager::getNavTypeIndexOf(Waypoint* wp)
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints)
foreach (Waypoint* p, waypointsEditable)
{
if (p->isNavigationType())
{
......@@ -584,10 +611,10 @@ int UASWaypointManager::getNavTypeIndexOf(Waypoint* wp)
int UASWaypointManager::getGlobalFrameCount()
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints)
foreach (Waypoint* p, waypointsEditable)
{
if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
......@@ -600,10 +627,10 @@ int UASWaypointManager::getGlobalFrameCount()
int UASWaypointManager::getGlobalFrameAndNavTypeCount()
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints) {
foreach (Waypoint* p, waypointsEditable) {
if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
{
i++;
......@@ -615,10 +642,10 @@ int UASWaypointManager::getGlobalFrameAndNavTypeCount()
int UASWaypointManager::getNavTypeCount()
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints) {
foreach (Waypoint* p, waypointsEditable) {
if (p->isNavigationType()) {
i++;
}
......@@ -629,10 +656,10 @@ int UASWaypointManager::getNavTypeCount()
int UASWaypointManager::getLocalFrameCount()
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints)
foreach (Waypoint* p, waypointsEditable)
{
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
{
......@@ -645,10 +672,10 @@ int UASWaypointManager::getLocalFrameCount()
int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in local frame
int i = 0;
foreach (Waypoint* p, waypoints)
foreach (Waypoint* p, waypointsEditable)
{
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
{
......@@ -665,10 +692,10 @@ int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
// Search through all waypoints,
// Search through all waypointsEditable,
// counting only those in mission frame
int i = 0;
foreach (Waypoint* p, waypoints)
foreach (Waypoint* p, waypointsEditable)
{
if (p->getFrame() == MAV_FRAME_MISSION)
{
......@@ -683,13 +710,18 @@ int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
return -1;
}
void UASWaypointManager::readWaypoints()
/**
* @param readToEdit If true, incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab.
*/
void UASWaypointManager::readWaypoints(bool readToEdit)
{
read_to_edit = readToEdit;
emit readGlobalWPFromUAS(true);
if(current_state == WP_IDLE) {
while(waypoints.size()>0) {
delete waypoints.back();
waypoints.pop_back();
while(waypointsEditable.size()>0) {
delete waypointsEditable.back();
waypointsEditable.pop_back();
}
......@@ -710,11 +742,11 @@ void UASWaypointManager::writeWaypoints()
{
if (current_state == WP_IDLE) {
// Send clear all if count == 0
if (waypoints.count() > 0) {
if (waypointsEditable.count() > 0) {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_count = waypoints.count();
current_count = waypointsEditable.count();
current_state = WP_SENDLIST;
current_wp_id = 0;
current_partner_systemid = uas.getUASID();
......@@ -736,7 +768,7 @@ void UASWaypointManager::writeWaypoints()
waypoint_buffer.push_back(new mavlink_mission_item_t);
mavlink_mission_item_t *cur_d = waypoint_buffer.back();
memset(cur_d, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros
const Waypoint *cur_s = waypoints.at(i);
const Waypoint *cur_s = waypointsEditable.at(i);
cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
......@@ -763,7 +795,7 @@ void UASWaypointManager::writeWaypoints()
//send the waypoint count to UAS (this starts the send transaction)
sendWaypointCount();
}
} else if (waypoints.count() == 0) {
} else if (waypointsEditable.count() == 0) {
sendWaypointClearAll();
} else {
//we're in another transaction, ignore command
......
......@@ -79,15 +79,19 @@ public:
/** @name Remote operations */
/*@{*/
void clearWaypointList(); ///< Sends the waypoint clear all message to the MAV
void readWaypoints(); ///< Requests the MAV's current waypoint list
void readWaypoints(bool read_to_edit=false); ///< Requests the MAV's current waypoint list.
void writeWaypoints(); ///< Sends the waypoint list to the MAV
int setCurrentWaypoint(quint16 seq); ///< Changes the current waypoint and sends the sequence number of the waypoint that should get the new target waypoint to the UAS
/*@}*/
/** @name Waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getWaypointList(void) {
return waypoints; ///< Returns a const reference to the waypoint list.
const QVector<Waypoint *> &getWaypointEditableList(void) {
return waypointsEditable; ///< Returns a const reference to the waypoint list.
}
const QVector<Waypoint *> &getWaypointViewOnlyList(void) {
return waypointsViewOnly; ///< Returns a const reference to the waypoint list.
}
const QVector<Waypoint *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list
const QVector<Waypoint *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
......@@ -125,6 +129,7 @@ public slots:
/** @name Waypoint list operations */
/*@{*/
void addWaypointEditable(Waypoint *wp, bool enforceFirstActive=true); ///< adds a new waypoint to the end of the editable list and changes its sequence number accordingly
void addWaypointViewOnly(Waypoint *wp); ///< adds a new waypoint to the end of the view-only list and changes its sequence number accordingly
Waypoint* createWaypoint(bool enforceFirstActive=true); ///< Creates a waypoint
int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
......@@ -140,6 +145,9 @@ signals:
void waypointEditableListChanged(void); ///< emits signal that the list of editable waypoints has been changed
void waypointEditableListChanged(int uasid); ///< emits signal that the list of editable waypoints has been changed
void waypointEditableChanged(int uasid, Waypoint* wp); ///< emits signal that a single editable waypoint has been changed
void waypointViewOnlyListChanged(void); ///< emits signal that the list of editable waypoints has been changed
void waypointViewOnlyListChanged(int uasid); ///< emits signal that the list of editable waypoints has been changed
void waypointViewOnlyChanged(int uasid, Waypoint* wp); ///< emits signal that a single editable waypoint has been changed
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string
void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters)
......@@ -155,9 +163,11 @@ private:
WaypointState current_state; ///< The current protocol state
quint8 current_partner_systemid; ///< The current protocol communication target system
quint8 current_partner_compid; ///< The current protocol communication target component
bool read_to_edit; ///< If true, after readWaypoints() incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab.
QVector<Waypoint *> waypoints; ///< local waypoint list (main storage)
Waypoint* currentWaypoint; ///< The currently used waypoint
QVector<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QVector<Waypoint *> waypointsEditable; ///< local editable waypoint list
Waypoint* currentWaypointEditable; ///< The currently used waypoint
QVector<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication
QTimer protocol_timer; ///< Timer to catch timeouts
};
......
......@@ -954,7 +954,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
{
if (uas)
{
const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
QColor color;
painter.setBrush(Qt::NoBrush);
......
......@@ -51,11 +51,13 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
{
m_ui->setupUi(this);
listLayout = new QVBoxLayout(m_ui->editableListWidget);
listLayout->setSpacing(0);
listLayout->setMargin(0);
listLayout->setAlignment(Qt::AlignTop);
m_ui->editableListWidget->setLayout(listLayout);
//EDIT TAB
editableListLayout = new QVBoxLayout(m_ui->editableListWidget);
editableListLayout->setSpacing(0);
editableListLayout->setMargin(0);
editableListLayout->setAlignment(Qt::AlignTop);
m_ui->editableListWidget->setLayout(editableListLayout);
// ADD WAYPOINT
// Connect add action, set right button icon and connect action to this class
......@@ -77,6 +79,17 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
//VIEW TAB
viewOnlyListLayout = new QVBoxLayout(m_ui->viewOnlyListWidget);
viewOnlyListLayout->setSpacing(0);
viewOnlyListLayout->setMargin(0);
viewOnlyListLayout->setAlignment(Qt::AlignTop);
m_ui->viewOnlyListWidget->setLayout(viewOnlyListLayout);
// REFRESH VIEW TAB
connect(m_ui->refreshButton, SIGNAL(clicked()), this, SLOT(refresh()));
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
......@@ -128,6 +141,8 @@ void WaypointList::setUAS(UASInterface* uas)
connect(uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void)));
connect(uas->getWaypointManager(), SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*)));
connect(uas->getWaypointManager(), SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void)));
connect(uas->getWaypointManager(), SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*)));
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)));
......@@ -164,15 +179,45 @@ void WaypointList::read()
{
if (uas)
{
uas->getWaypointManager()->readWaypoints();
uas->getWaypointManager()->readWaypoints(true);
}
}
void WaypointList::refresh()
{
if (uas)
{
uas->getWaypointManager()->readWaypoints(false);
}
}
void WaypointList::add()
void WaypointList::addEditable()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
Waypoint *wp;
if (waypoints.size() > 0)
{
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1);
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getParam1(), last->getParam2(), last->getParam3(), last->getParam4(),
last->getAutoContinue(), false, last->getFrame(), last->getAction());
uas->getWaypointManager()->addWaypointEditable(wp);
}
else
{
// Create first waypoint at current MAV position
addCurrentPositionWaypoint();
}
}
}
void WaypointList::addViewOnly()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointViewOnlyList();
Waypoint *wp;
if (waypoints.size() > 0)
{
......@@ -194,7 +239,7 @@ void WaypointList::addCurrentPositionWaypoint()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
Waypoint *wp;
Waypoint *last = 0;
if (waypoints.size() > 0)
......@@ -257,13 +302,13 @@ void WaypointList::currentWaypointChanged(quint16 seq)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointEditableView* widget = wpViews.find(waypoints[i]).value();
WaypointEditableView* widget = wpEditableViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
......@@ -281,19 +326,72 @@ void WaypointList::currentWaypointChanged(quint16 seq)
void WaypointList::updateWaypoint(int uas, Waypoint* wp)
{
Q_UNUSED(uas);
WaypointEditableView *wpv = wpViews.value(wp);
WaypointEditableView *wpv = wpEditableViews.value(wp);
wpv->updateValues();
}
void WaypointList::waypointViewOnlyListChanged()
{
if (uas) {
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointViewOnlyList();
if (!wpViewOnlyViews.empty()) {
QMapIterator<Waypoint*,WaypointViewOnlyView*> viewIt(wpViewOnlyViews);
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()) {
WaypointViewOnlyView* widget = wpViewOnlyViews.find(cur).value();
widget->hide();
editableListLayout->removeWidget(widget);
wpViewOnlyViews.remove(cur);
}
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++) {
Waypoint *wp = waypoints[i];
if (!wpViewOnlyViews.contains(wp)) {
WaypointViewOnlyView* wpview = new WaypointViewOnlyView(wp, this);
wpViewOnlyViews.insert(wp, wpview);
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
viewOnlyListLayout->insertWidget(i, wpview);
}
WaypointViewOnlyView *wpv = wpViewOnlyViews.value(wp);
//check if ordering has changed
if(viewOnlyListLayout->itemAt(i)->widget() != wpv) {
viewOnlyListLayout->removeWidget(wpv);
viewOnlyListLayout->insertWidget(i, wpv);
}
wpv->updateValues(); // update the values of the ui elements in the view
}
this->setUpdatesEnabled(true);
loadFileGlobalWP = false;
}
}
void WaypointList::waypointEditableListChanged()
{
if (uas) {
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
if (!wpViews.empty()) {
QMapIterator<Waypoint*,WaypointEditableView*> viewIt(wpViews);
if (!wpEditableViews.empty()) {
QMapIterator<Waypoint*,WaypointEditableView*> viewIt(wpEditableViews);
viewIt.toFront();
while(viewIt.hasNext()) {
viewIt.next();
......@@ -305,10 +403,10 @@ void WaypointList::waypointEditableListChanged()
}
}
if (i == waypoints.size()) {
WaypointEditableView* widget = wpViews.find(cur).value();
WaypointEditableView* widget = wpEditableViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
editableListLayout->removeWidget(widget);
wpEditableViews.remove(cur);
}
}
}
......@@ -316,22 +414,22 @@ void WaypointList::waypointEditableListChanged()
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++) {
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp)) {
if (!wpEditableViews.contains(wp)) {
WaypointEditableView* wpview = new WaypointEditableView(wp, this);
wpViews.insert(wp, wpview);
wpEditableViews.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))); commented, because unused
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
listLayout->insertWidget(i, wpview);
//connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
editableListLayout->insertWidget(i, wpview);
}
WaypointEditableView *wpv = wpViews.value(wp);
WaypointEditableView *wpv = wpEditableViews.value(wp);
//check if ordering has changed
if(listLayout->itemAt(i)->widget() != wpv) {
listLayout->removeWidget(wpv);
listLayout->insertWidget(i, wpv);
if(editableListLayout->itemAt(i)->widget() != wpv) {
editableListLayout->removeWidget(wpv);
editableListLayout->insertWidget(i, wpv);
}
wpv->updateValues(); // update the values of the ui elements in the view
......@@ -348,31 +446,31 @@ void WaypointList::waypointEditableListChanged()
// // Prevent updates to prevent visual flicker
// this->setUpdatesEnabled(false);
// // Get all waypoints
// const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
// const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
//// // Store the current state, then check which widgets to update
//// // and which ones to delete
//// QList<Waypoint*> oldWaypoints = wpViews.keys();
//// QList<Waypoint*> oldWaypoints = wpEditableViews.keys();
//// foreach (Waypoint* wp, waypoints)
//// {
//// WaypointEditableView* wpview;
//// // Create any new waypoint
//// if (!wpViews.contains(wp))
//// if (!wpEditableViews.contains(wp))
//// {
//// wpview = new WaypointEditableView(wp, this);
//// wpViews.insert(wp, wpview);
//// wpEditableViews.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);
//// editableListLayout->addWidget(wpview);
//// }
//// else
//// {
//// // Update existing waypoints
//// wpview = wpViews.value(wp);
//// wpview = wpEditableViews.value(wp);
//// }
//// // Mark as updated by removing from old list
......@@ -386,18 +484,18 @@ void WaypointList::waypointEditableListChanged()
//// foreach (Waypoint* wp, oldWaypoints)
//// {
//// // Delete waypoint view and entry in list
//// WaypointEditableView* wpv = wpViews.value(wp);
//// WaypointEditableView* wpv = wpEditableViews.value(wp);
//// if (wpv)
//// {
//// listLayout->removeWidget(wpv);
//// editableListLayout->removeWidget(wpv);
//// delete wpv;
//// }
//// wpViews.remove(wp);
//// wpEditableViews.remove(wp);
//// }
// if (!wpViews.empty())
// if (!wpEditableViews.empty())
// {
// QMapIterator<Waypoint*,WaypointEditableView*> viewIt(wpViews);
// QMapIterator<Waypoint*,WaypointEditableView*> viewIt(wpEditableViews);
// viewIt.toFront();
// while(viewIt.hasNext())
// {
......@@ -413,13 +511,13 @@ void WaypointList::waypointEditableListChanged()
// }
// if (i == waypoints.size())
// {
// WaypointEditableView* widget = wpViews.find(cur).value();
// WaypointEditableView* widget = wpEditableViews.find(cur).value();
// if (widget)
// {
// widget->hide();
// listLayout->removeWidget(widget);
// editableListLayout->removeWidget(widget);
// }
// wpViews.remove(cur);
// wpEditableViews.remove(cur);
// }
// }
// }
......@@ -428,19 +526,19 @@ void WaypointList::waypointEditableListChanged()
// for(int i = 0; i < waypoints.size(); i++)
// {
// Waypoint *wp = waypoints[i];
// if (!wpViews.contains(wp))
// if (!wpEditableViews.contains(wp))
// {
// WaypointEditableView* wpview = new WaypointEditableView(wp, this);
// wpViews.insert(wp, wpview);
// wpEditableViews.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)));
// }
// WaypointEditableView *wpv = wpViews.value(wp);
// WaypointEditableView *wpv = wpEditableViews.value(wp);
// wpv->updateValues(); // update the values of the ui elements in the view
// listLayout->addWidget(wpv);
// editableListLayout->addWidget(wpv);
// }
// this->setUpdatesEnabled(true);
......@@ -451,7 +549,7 @@ void WaypointList::waypointEditableListChanged()
void WaypointList::moveUp(Waypoint* wp)
{
if (uas) {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
//get the current position of wp in the local storage
int i;
......@@ -470,7 +568,7 @@ void WaypointList::moveUp(Waypoint* wp)
void WaypointList::moveDown(Waypoint* wp)
{
if (uas) {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
//get the current position of wp in the local storage
int i;
......@@ -512,9 +610,9 @@ void WaypointList::on_clearWPListButton_clicked()
if (uas) {
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++)
WaypointEditableView* widget = wpViews.find(waypoints[0]).value();
WaypointEditableView* widget = wpEditableViews.find(waypoints[0]).value();
widget->remove();
}
} else {
......@@ -531,7 +629,7 @@ void WaypointList::on_clearWPListButton_clicked()
//{
// if (uas)
// {
// const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
// const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
// if (waypoints.size() > 0)
// {
// Waypoint *temp = waypoints.at(indexWP);
......@@ -563,9 +661,9 @@ void WaypointList::on_clearWPListButton_clicked()
void WaypointList::clearWPWidget()
{
if (uas) {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointEditableList();
while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++)
WaypointEditableView* widget = wpViews.find(waypoints[0]).value();
WaypointEditableView* widget = wpEditableViews.find(waypoints[0]).value();
widget->remove();
}
}
......
......@@ -69,10 +69,14 @@ public slots:
void loadWaypoints();
/** @brief Transmit the local waypoint list to the UAS */
void transmit();
/** @brief Read the remote waypoint list */
/** @brief Read the remote waypoint list to both tabs */
void read();
/** @brief Add a waypoint */
void add();
/** @brief Read the remote waypoint list to "view"-tab only*/
void refresh();
/** @brief Add a waypoint to "edit"-tab */
void addEditable();
/** @brief Add a waypoint to "view"-tab */
void addViewOnly();
/** @brief Add a waypoint at the current MAV position */
void addCurrentPositionWaypoint();
/** @brief Add a waypoint by mouse click over the map */
......@@ -86,8 +90,10 @@ public slots:
void currentWaypointChanged(quint16 seq);
/** @brief The waypoint manager informs that one waypoint was changed */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief The waypoint manager informs that the waypoint list was changed */
/** @brief The waypoint manager informs that the editable waypoint list was changed */
void waypointEditableListChanged(void);
/** @brief The waypoint manager informs that the waypoint list on the MAV was changed */
void waypointViewOnlyListChanged(void);
// /** @brief The MapWidget informs that a waypoint global was changed on the map */
// void waypointGlobalChanged(const QPointF coordinate, const int indexWP);
......@@ -115,8 +121,10 @@ protected:
virtual void changeEvent(QEvent *e);
protected:
QMap<Waypoint*, WaypointEditableView*> wpViews;
QVBoxLayout* listLayout;
QMap<Waypoint*, WaypointEditableView*> wpEditableViews;
QMap<Waypoint*, WaypointViewOnlyView*> wpViewOnlyViews;
QVBoxLayout* viewOnlyListLayout;
QVBoxLayout* editableListLayout;
UASInterface* uas;
double mavX;
double mavY;
......
......@@ -294,7 +294,7 @@ Pixhawk3DWidget::setWaypoint(void)
{
if (uas) {
const QVector<Waypoint *> waypoints =
uas->getWaypointManager()->getWaypointList();
uas->getWaypointManager()->getWaypointEditableList();
Waypoint* waypoint = waypoints.at(selectedWpIndex);
if (frame == MAV_FRAME_GLOBAL) {
......@@ -341,7 +341,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
if (uas) {
bool ok;
const QVector<Waypoint *> waypoints =
uas->getWaypointManager()->getWaypointList();
uas->getWaypointManager()->getWaypointEditableList();
Waypoint* waypoint = waypoints.at(selectedWpIndex);
double altitude = waypoint->getZ();
......@@ -367,7 +367,7 @@ Pixhawk3DWidget::clearAllWaypoints(void)
{
if (uas) {
const QVector<Waypoint *> waypoints =
uas->getWaypointManager()->getWaypointList();
uas->getWaypointManager()->getWaypointEditableList();
for (int i = waypoints.size() - 1; i >= 0; --i) {
uas->getWaypointManager()->removeWaypoint(i);
}
......
......@@ -73,7 +73,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
removeChild(0, getNumChildren());
}
const QVector<Waypoint *>& list = uas->getWaypointManager()->getWaypointList();
const QVector<Waypoint *>& list = uas->getWaypointManager()->getWaypointEditableList();
for (int i = 0; i < list.size(); i++) {
Waypoint* wp = list.at(i);
......
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