Commit deb6ba86 authored by tecnosapiens's avatar tecnosapiens

change view when add Slugs Link

parent 1ef9ae7b
...@@ -153,6 +153,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ ...@@ -153,6 +153,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
current_partner_compid = 0; current_partner_compid = 0;
protocol_timer.stop(); protocol_timer.stop();
emit readGlobalWPFromUAS(false);
emit updateStatusString("done."); emit updateStatusString("done.");
qDebug() << "got all waypoints from ID " << systemId; qDebug() << "got all waypoints from ID " << systemId;
...@@ -294,6 +295,7 @@ void UASWaypointManager::localAddWaypoint(Waypoint *wp) ...@@ -294,6 +295,7 @@ void UASWaypointManager::localAddWaypoint(Waypoint *wp)
{ {
wp->setId(waypoints.size()); wp->setId(waypoints.size());
waypoints.insert(waypoints.size(), wp); waypoints.insert(waypoints.size(), wp);
emit waypointListChanged(); emit waypointListChanged();
} }
} }
...@@ -417,6 +419,7 @@ void UASWaypointManager::clearWaypointList() ...@@ -417,6 +419,7 @@ void UASWaypointManager::clearWaypointList()
void UASWaypointManager::readWaypoints() void UASWaypointManager::readWaypoints()
{ {
emit readGlobalWPFromUAS(true);
if(current_state == WP_IDLE) if(current_state == WP_IDLE)
{ {
while(waypoints.size()>0) while(waypoints.size()>0)
...@@ -424,6 +427,7 @@ void UASWaypointManager::readWaypoints() ...@@ -424,6 +427,7 @@ void UASWaypointManager::readWaypoints()
Waypoint *t = waypoints.back(); Waypoint *t = waypoints.back();
delete t; delete t;
waypoints.pop_back(); waypoints.pop_back();
} }
protocol_timer.start(PROTOCOL_TIMEOUT_MS); protocol_timer.start(PROTOCOL_TIMEOUT_MS);
...@@ -435,6 +439,7 @@ void UASWaypointManager::readWaypoints() ...@@ -435,6 +439,7 @@ void UASWaypointManager::readWaypoints()
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER; current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
sendWaypointRequestList(); sendWaypointRequestList();
} }
} }
...@@ -570,6 +575,8 @@ void UASWaypointManager::sendWaypointRequestList() ...@@ -570,6 +575,8 @@ void UASWaypointManager::sendWaypointRequestList()
MG::SLEEP::usleep(PROTOCOL_DELAY_MS * 1000); MG::SLEEP::usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint list request to ID " << wprl.target_system; qDebug() << "sent waypoint list request to ID " << wprl.target_system;
} }
void UASWaypointManager::sendWaypointRequest(quint16 seq) void UASWaypointManager::sendWaypointRequest(quint16 seq)
......
...@@ -122,6 +122,7 @@ signals: ...@@ -122,6 +122,7 @@ signals:
void updateStatusString(const QString &); ///< emits the current status string void updateStatusString(const QString &); ///< emits the current status string
void loadWPFile(); ///< emits signal that a file wp has been load void loadWPFile(); ///< emits signal that a file wp has been load
void readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS
private: private:
UAS &uas; ///< Reference to the corresponding UAS UAS &uas; ///< Reference to the corresponding UAS
......
...@@ -573,7 +573,8 @@ void MainWindow::UASCreated(UASInterface* uas) ...@@ -573,7 +573,8 @@ void MainWindow::UASCreated(UASInterface* uas)
SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas); SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
if (mav2) { if (mav2) {
dataWidget->addUAS(uas); dataWidget->addUAS(uas);
loadSlugsView(); //loadSlugsView();
loadGlobalOperatorView();
} }
} }
} }
......
...@@ -92,6 +92,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : ...@@ -92,6 +92,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
isGlobalWP = false; isGlobalWP = false;
isLocalWP = false; isLocalWP = false;
loadFileGlobalWP = false; loadFileGlobalWP = false;
readGlobalWP = false;
centerMapCoordinate.setX(0.0); centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0); centerMapCoordinate.setY(0.0);
...@@ -133,6 +134,8 @@ void WaypointList::setUAS(UASInterface* uas) ...@@ -133,6 +134,8 @@ void WaypointList::setUAS(UASInterface* uas)
connect(&uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void))); connect(&uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void)));
connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(&uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP())); connect(&uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
connect(&uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
} }
} }
...@@ -250,6 +253,8 @@ void WaypointList::addCurrentPositonWaypoint() ...@@ -250,6 +253,8 @@ void WaypointList::addCurrentPositonWaypoint()
void WaypointList::updateStatusLabel(const QString &string) void WaypointList::updateStatusLabel(const QString &string)
{ {
m_ui->statusLabel->setText(string); m_ui->statusLabel->setText(string);
} }
void WaypointList::changeCurrentWaypoint(quint16 seq) void WaypointList::changeCurrentWaypoint(quint16 seq)
...@@ -341,7 +346,7 @@ void WaypointList::waypointListChanged() ...@@ -341,7 +346,7 @@ void WaypointList::waypointListChanged()
WaypointGlobalView *wpgv = wpGlobalViews.value(wp); WaypointGlobalView *wpgv = wpGlobalViews.value(wp);
wpgv->updateValues(); wpgv->updateValues();
listLayout->addWidget(wpgv); listLayout->addWidget(wpgv);
if(loadFileGlobalWP) if(loadFileGlobalWP || readGlobalWP)
{ {
emit createWaypointAtMap(QPointF(wp->getX(),wp->getY())); emit createWaypointAtMap(QPointF(wp->getX(),wp->getY()));
qDebug()<<"Emitiendo Pos: "<<wp->getX()<<" - "<<wp->getY(); qDebug()<<"Emitiendo Pos: "<<wp->getX()<<" - "<<wp->getY();
...@@ -637,3 +642,8 @@ void WaypointList::setIsLoadFileWP() ...@@ -637,3 +642,8 @@ void WaypointList::setIsLoadFileWP()
{ {
loadFileGlobalWP = true; loadFileGlobalWP = true;
} }
void WaypointList::setIsReadGlobalWP(bool value)
{
readGlobalWP = value;
}
...@@ -103,6 +103,7 @@ public slots: ...@@ -103,6 +103,7 @@ public slots:
void removeWaypoint(Waypoint* wp); void removeWaypoint(Waypoint* wp);
void setIsLoadFileWP(); void setIsLoadFileWP();
void setIsReadGlobalWP(bool value);
...@@ -131,6 +132,7 @@ protected: ...@@ -131,6 +132,7 @@ protected:
bool isLocalWP; bool isLocalWP;
QPointF centerMapCoordinate; QPointF centerMapCoordinate;
bool loadFileGlobalWP; bool loadFileGlobalWP;
bool readGlobalWP;
private: private:
Ui::WaypointList *m_ui; Ui::WaypointList *m_ui;
......
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