Browse Source

Improved performance of 2D map, trails need further debugging

QGC4.4
lm 15 years ago
parent
commit
a33541b960
  1. 6
      src/GAudioOutput.cc
  2. 3
      src/ui/HUD.cc
  3. 2
      src/ui/MainWindow.cc
  4. 199
      src/ui/MapWidget.cc
  5. 11
      src/ui/MapWidget.h
  6. 20
      src/ui/QGCDataPlot2D.cc
  7. 14
      src/ui/WaypointList.cc

6
src/GAudioOutput.cc

@ -144,9 +144,6 @@ muted(false)
GAudioOutput::~GAudioOutput() GAudioOutput::~GAudioOutput()
{ {
QSettings settings;
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", muted);
settings.sync();
#ifdef _MSC_VER2 #ifdef _MSC_VER2
::CoUninitialize(); ::CoUninitialize();
#endif #endif
@ -155,6 +152,9 @@ GAudioOutput::~GAudioOutput()
void GAudioOutput::mute(bool mute) void GAudioOutput::mute(bool mute)
{ {
this->muted = mute; this->muted = mute;
QSettings settings;
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", muted);
settings.sync();
} }
bool GAudioOutput::isMuted() bool GAudioOutput::isMuted()

3
src/ui/HUD.cc

@ -117,6 +117,9 @@ HUD::HUD(int width, int height, QWidget* parent)
// Set auto fill to false // Set auto fill to false
setAutoFillBackground(false); setAutoFillBackground(false);
// Set minimum size
setMinimumSize(80, 60);
// Fill with black background // Fill with black background
QImage fill = QImage(width, height, QImage::Format_Indexed8); QImage fill = QImage(width, height, QImage::Format_Indexed8);
fill.setNumColors(3); fill.setNumColors(3);

2
src/ui/MainWindow.cc

@ -703,7 +703,7 @@ void MainWindow::connectCommonWidgets()
if (mapWidget && waypointsDockWidget->widget()) if (mapWidget && waypointsDockWidget->widget())
{ {
// clear path create on the map // clear path create on the map
connect(waypointsDockWidget->widget(), SIGNAL(clearPathclicked()), mapWidget, SLOT(clearPath())); connect(waypointsDockWidget->widget(), SIGNAL(clearPathclicked()), mapWidget, SLOT(clearWaypoints()));
// add Waypoint widget in the WaypointList widget when mouse clicked // add Waypoint widget in the WaypointList widget when mouse clicked
connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF))); connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));

199
src/ui/MapWidget.cc

@ -30,6 +30,7 @@ MapWidget::MapWidget(QWidget *parent) :
uasIcons(), uasIcons(),
uasTrails(), uasTrails(),
mav(NULL), mav(NULL),
lastUpdate(0),
m_ui(new Ui::MapWidget) m_ui(new Ui::MapWidget)
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
@ -61,6 +62,10 @@ MapWidget::MapWidget(QWidget *parent) :
overlay->setVisible(false); overlay->setVisible(false);
mc->addLayer(overlay); mc->addLayer(overlay);
// MAV FLIGHT TRACKS
tracks = new qmapcontrol::MapLayer("Tracking", mapadapter);
mc->addLayer(tracks);
// WAYPOINT LAYER // WAYPOINT LAYER
// create a layer with the mapadapter and type GeometryLayer (for waypoints) // create a layer with the mapadapter and type GeometryLayer (for waypoints)
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter); geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
@ -139,12 +144,14 @@ MapWidget::MapWidget(QWidget *parent) :
QPushButton* zoomin = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this); QPushButton* zoomin = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this); QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this);
createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this); createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this);
clearTracking = new QPushButton(QIcon(""), "", this);
followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this); followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this);
zoomin->setMaximumWidth(50); zoomin->setMaximumWidth(30);
zoomout->setMaximumWidth(50); zoomout->setMaximumWidth(30);
createPath->setMaximumWidth(50); createPath->setMaximumWidth(30);
followgps->setMaximumWidth(50); clearTracking->setMaximumWidth(30);
followgps->setMaximumWidth(30);
// Set checkable buttons // Set checkable buttons
// TODO: Currently checked buttons are are very difficult to distinguish when checked. // TODO: Currently checked buttons are are very difficult to distinguish when checked.
@ -160,9 +167,10 @@ MapWidget::MapWidget(QWidget *parent) :
innerlayout->addWidget(zoomout, 1, 0); innerlayout->addWidget(zoomout, 1, 0);
innerlayout->addWidget(followgps, 2, 0); innerlayout->addWidget(followgps, 2, 0);
innerlayout->addWidget(createPath, 3, 0); innerlayout->addWidget(createPath, 3, 0);
innerlayout->addWidget(clearTracking, 4, 0);
// Add spacers to compress buttons on the top left // Add spacers to compress buttons on the top left
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 4, 0); innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 5, 0);
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 0, 1, 0, 5); innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 0, 1, 0, 6);
innerlayout->setRowStretch(0, 1); innerlayout->setRowStretch(0, 1);
innerlayout->setRowStretch(1, 100); innerlayout->setRowStretch(1, 100);
mc->setLayout(innerlayout); mc->setLayout(innerlayout);
@ -206,9 +214,8 @@ MapWidget::MapWidget(QWidget *parent) :
// Configure the WP Path's pen // Configure the WP Path's pen
pointPen = new QPen(QColor(0, 255,0)); pointPen = new QPen(QColor(0, 255,0));
pointPen->setWidth(3); pointPen->setWidth(3);
waypointPath = new qmapcontrol::LineString (wps, "Waypoint path", pointPen);
path = new qmapcontrol::LineString (wps, "UAV Path", pointPen); mc->layer("Waypoints")->addGeometry(waypointPath);
mc->layer("Waypoints")->addGeometry(path);
//Camera Control //Camera Control
// CAMERA INDICATOR LAYER // CAMERA INDICATOR LAYER
@ -310,8 +317,6 @@ void MapWidget::createPathButtonClicked(bool checked)
{ {
Q_UNUSED(checked); Q_UNUSED(checked);
if (createPath->isChecked()) if (createPath->isChecked())
{ {
// change the cursor shape // change the cursor shape
@ -329,14 +334,12 @@ void MapWidget::createPathButtonClicked(bool checked)
// path->setPoints(wps); // path->setPoints(wps);
// mc->layer("Waypoints")->addGeometry(path); // mc->layer("Waypoints")->addGeometry(path);
// wpIndex.clear(); // wpIndex.clear();
}
else
} else { {
this->setCursor(Qt::ArrowCursor); this->setCursor(Qt::ArrowCursor);
mc->setMouseMode(qmapcontrol::MapControl::Panning); mc->setMouseMode(qmapcontrol::MapControl::Panning);
} }
} }
@ -351,15 +354,13 @@ void MapWidget::createPathButtonClicked(bool checked)
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate) void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate)
{ {
//qDebug() << mc->mouseMode();
qDebug() << mc->mouseMode();
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked()) if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked())
{ {
// Create waypoint name // Create waypoint name
QString str; QString str;
str = QString("%1").arg(path->numberOfPoints()); str = QString("%1").arg(waypointPath->numberOfPoints());
// create the WP and set everything in the LineString to display the path // create the WP and set everything in the LineString to display the path
Waypoint2DIcon* tempCirclePoint; Waypoint2DIcon* tempCirclePoint;
@ -376,27 +377,27 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str); qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint); wps.append(tempPoint);
path->addPoint(tempPoint); waypointPath->addPoint(tempPoint);
wpIndex.insert(str,tempPoint); wpIndex.insert(str,tempPoint);
// Refresh the screen // Refresh the screen
mc->updateRequestNew(); mc->updateRequest(tempPoint->boundingBox().toRect());
// emit signal mouse was clicked // emit signal mouse was clicked
emit captureMapCoordinateClick(coordinate); emit captureMapCoordinateClick(coordinate);
} }
} }
void MapWidget::createWaypointGraphAtMap(const QPointF coordinate) void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
{ {
if (!wpExists(coordinate)){ if (!wpExists(coordinate))
{
// Create waypoint name // Create waypoint name
QString str; QString str;
str = QString("%1").arg(path->numberOfPoints()); str = QString("%1").arg(waypointPath->numberOfPoints());
// create the WP and set everything in the LineString to display the path // create the WP and set everything in the LineString to display the path
//CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str); //CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
@ -416,13 +417,13 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str); Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint); wps.append(tempPoint);
path->addPoint(tempPoint); waypointPath->addPoint(tempPoint);
wpIndex.insert(str,tempPoint); wpIndex.insert(str,tempPoint);
qDebug()<<"Funcion createWaypointGraphAtMap WP= "<<str<<" -> x= "<<tempPoint->latitude()<<" y= "<<tempPoint->longitude(); qDebug()<<"Funcion createWaypointGraphAtMap WP= "<<str<<" -> x= "<<tempPoint->latitude()<<" y= "<<tempPoint->longitude();
// Refresh the screen // Refresh the screen
mc->updateRequestNew(); mc->updateRequest(tempPoint->boundingBox().toRect());
} }
//// // emit signal mouse was clicked //// // emit signal mouse was clicked
@ -456,7 +457,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
waypointIsDrag = true; waypointIsDrag = true;
// Refresh the screen // Refresh the screen
mc->updateRequestNew(); mc->updateRequest(geom->boundingBox().toRect());
int temp = 0; int temp = 0;
qmapcontrol::Point* point2Find; qmapcontrol::Point* point2Find;
@ -505,10 +506,6 @@ MapWidget::~MapWidget()
*/ */
void MapWidget::addUAS(UASInterface* uas) void MapWidget::addUAS(UASInterface* uas)
{ {
if(mav != NULL)
{
disconnect(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))); connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
} }
@ -517,7 +514,11 @@ void MapWidget::activeUASSet(UASInterface* uas)
if (uas) if (uas)
{ {
mav = uas; mav = uas;
path->setPen(new QPen(mav->getColor())); QColor color = mav->getColor();
color.setAlphaF(0.6);
QPen* pen = new QPen(color);
pen->setWidth(3.0);
// FIXME Load waypoints of this system
} }
} }
@ -534,62 +535,73 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
{ {
Q_UNUSED(usec); Q_UNUSED(usec);
Q_UNUSED(alt); // FIXME Use altitude Q_UNUSED(alt); // FIXME Use altitude
// create a LineString
//QList<Point*> points;
// Points with a circle
// A QPen can be used to customize the
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
MAV2DIcon* p;
if (!uasIcons.contains(uas->getUASID()))
{
// Get the UAS color
QColor uasColor = uas->getColor();
// Icon
QPen* pointpen = new QPen(uasColor);
qDebug() << uas->getUASName();
p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
tracks->addGeometry(p);
// Line
// A QPen also can use transparency
QList<qmapcontrol::Point*> points;
points.append(new qmapcontrol::Point(lat, lon, ""));
QPen* linepen = new QPen(uasColor.darker());
linepen->setWidth(2);
// Create tracking line string
qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen);
uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
mc->layer("Tracking")->addGeometry(ls);
}
else
{
p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
if (p)
{
p->setCoordinate(QPointF(lat, lon));
p->setYaw(uas->getYaw());
}
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, ""));
}
//mc->updateRequestNew();//(uasTrails.value(uas->getUASID())->boundingBox().toRect());
// Limit the position update rate
quint64 currTime = MG::TIME::getGroundTimeNow(); quint64 currTime = MG::TIME::getGroundTimeNow();
if (currTime - lastUpdate > 90) if (currTime - lastUpdate > 120)
{ {
lastUpdate = currTime; lastUpdate = currTime;
// create a LineString // Sets the view to the interesting area
//QList<Point*> points; if (followgps->isChecked())
// Points with a circle
// A QPen can be used to customize the
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
if (!uasIcons.contains(uas->getUASID()))
{ {
// Get the UAS color updatePosition(0, lat, lon);
QColor uasColor = uas->getColor();
// Icon
QPen* pointpen = new QPen(uasColor);
qDebug() << uas->getUASName();
MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
geomLayer->addGeometry(p);
// Line
// A QPen also can use transparency
QList<qmapcontrol::Point*> points;
points.append(new qmapcontrol::Point(lat, lon, ""));
QPen* linepen = new QPen(uasColor.darker());
linepen->setWidth(2);
// Add the Points and the QPen to a LineString
qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen);
uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
geomLayer->addGeometry(ls);
} }
else else
{ {
MAV2DIcon* p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID())); // Refresh the screen
if (p) //mc->updateRequestNew();
{
p->setCoordinate(QPointF(lat, lon));
p->setYaw(uas->getYaw());
}
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, ""));
} }
// Connect click events of the layer to this object
// connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)),
// this, SLOT(geometryClicked(Geometry*, QPoint)));
// Sets the view to the interesting area
updatePosition(0, lat, lon);
} }
} }
@ -677,23 +689,36 @@ void MapWidget::changeEvent(QEvent *e)
break; break;
} }
} }
void MapWidget::clearPath()
void MapWidget::clearWaypoints()
{ {
// Clear the previous WP track // Clear the previous WP track
mc->layer("Waypoints")->clearGeometries(); mc->layer("Waypoints")->clearGeometries();
wps.clear(); wps.clear();
path->setPoints(wps); waypointPath->setPoints(wps);
mc->layer("Waypoints")->addGeometry(path); mc->layer("Waypoints")->addGeometry(waypointPath);
wpIndex.clear(); wpIndex.clear();
mc->updateRequestNew(); mc->updateRequest(waypointPath->boundingBox().toRect());
if(createPath->isChecked()) if(createPath->isChecked())
{ {
createPath->click(); createPath->click();
} }
}
void MapWidget::clearPath()
{
mc->layer("Tracking")->clearGeometries();
foreach (qmapcontrol::LineString* ls, uasTrails)
{
QPen* linepen = ls->pen();
delete ls;
qmapcontrol::LineString* lsNew = new qmapcontrol::LineString(QList<qmapcontrol::Point*>(), "", linepen);
mc->layer("Tracking")->addGeometry(lsNew);
}
// FIXME update this with update request only for bounding box of trails
mc->updateRequest(QRect(0, 0, width(), height()));
} }
void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon) void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon)
@ -714,7 +739,7 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa
point2Find->setCoordinate(coordinate); point2Find->setCoordinate(coordinate);
// Refresh the screen // Refresh the screen
mc->updateRequestNew(); mc->updateRequest(point2Find->boundingBox().toRect());
} }

11
src/ui/MapWidget.h

@ -71,7 +71,9 @@ public slots:
void updateCameraPosition(double distance, double bearing, QString dir); void updateCameraPosition(double distance, double bearing, QString dir);
QPointF getPointxBearing_Range(double lat1, double lon1, double bearing, double distance); QPointF getPointxBearing_Range(double lat1, double lon1, double bearing, double distance);
//ROCA /** @brief Clear the waypoints overlay layer */
void clearWaypoints();
/** @brief Clear the UAV tracks on the map */
void clearPath(); void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon); void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
void drawBorderCamAtMap(bool status); void drawBorderCamAtMap(bool status);
@ -96,6 +98,7 @@ protected:
QPushButton* followgps; QPushButton* followgps;
QPushButton* createPath; QPushButton* createPath;
QPushButton* clearTracking;
QLabel* gpsposition; QLabel* gpsposition;
QMenu* mapMenu; QMenu* mapMenu;
QPushButton* mapButton; QPushButton* mapButton;
@ -104,6 +107,7 @@ protected:
qmapcontrol::MapAdapter* mapadapter; ///< Adapter to load the map data qmapcontrol::MapAdapter* mapadapter; ///< Adapter to load the map data
qmapcontrol::Layer* l; ///< Current map layer (background) qmapcontrol::Layer* l; ///< Current map layer (background)
qmapcontrol::Layer* overlay; ///< Street overlay (foreground) qmapcontrol::Layer* overlay; ///< Street overlay (foreground)
qmapcontrol::Layer* tracks; ///< Layer for UAV tracks
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
//only for experiment //only for experiment
@ -132,9 +136,6 @@ protected:
void createWaypointGraphAtMap (const QPointF coordinate); void createWaypointGraphAtMap (const QPointF coordinate);
void mapproviderSelected(QAction* action); void mapproviderSelected(QAction* action);
signals: signals:
//void movePoint(QPointF newCoord); //void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA void captureMapCoordinateClick(const QPointF coordinate); //ROCA
@ -145,8 +146,8 @@ protected:
private: private:
Ui::MapWidget *m_ui; Ui::MapWidget *m_ui;
QList<qmapcontrol::Point*> wps; QList<qmapcontrol::Point*> wps;
qmapcontrol::LineString* waypointPath;
QHash <QString, qmapcontrol::Point*> wpIndex; QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen; QPen* pointPen;
int wpExists(const QPointF coordinate); int wpExists(const QPointF coordinate);
bool waypointIsDrag; bool waypointIsDrag;

20
src/ui/QGCDataPlot2D.cc

@ -307,7 +307,8 @@ void QGCDataPlot2D::selectFile()
void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFilter) void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFilter)
{ {
qDebug() << "LOADING RAW LOG!"; Q_UNUSED(xAxisName);
Q_UNUSED(yAxisFilter);
if (logFile != NULL) if (logFile != NULL)
{ {
@ -320,23 +321,6 @@ void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFil
connect(compressor, SIGNAL(logProcessingStatusChanged(QString)), MainWindow::instance(), SLOT(showStatusMessage(QString))); connect(compressor, SIGNAL(logProcessingStatusChanged(QString)), MainWindow::instance(), SLOT(showStatusMessage(QString)));
connect(compressor, SIGNAL(finishedFile(QString)), this, SLOT(loadFile(QString))); connect(compressor, SIGNAL(finishedFile(QString)), this, SLOT(loadFile(QString)));
compressor->startCompression(); compressor->startCompression();
// // Block UI
// QProgressDialog progress("Transforming RAW log file to CSV", "Abort Transformation", 0, 1, this);
// progress.setWindowModality(Qt::WindowModal);
// while (!compressor->isFinished())
// {
// MG::SLEEP::usleep(100000);
//// progress.setMaximum(compressor->getDataLines());
//// progress.setValue(compressor->getCurrentLine());
// }
// // Enforce end
// progress.setMaximum(compressor->getDataLines());
// progress.setValue(compressor->getDataLines());
// Done with preprocessing - now load csv log
//loadFile(logFile->fileName());
} }
/** /**

14
src/ui/WaypointList.cc

@ -197,20 +197,28 @@ void WaypointList::add()
{ {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList(); const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
Waypoint *wp;
if (waypoints.size() > 0) if (waypoints.size() > 0)
{ {
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1); Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(),
last->getHoldTime(), last->getFrame(), last->getAction()); last->getHoldTime(), last->getFrame(), last->getAction());
uas->getWaypointManager().addWaypoint(wp); uas->getWaypointManager().addWaypoint(wp);
} }
else else
{ {
//isLocalWP = true; // Create global frame waypoint per default
Waypoint *wp = new Waypoint(0, uas->getLongitude(), uas->getLatitude(), uas->getAltitude(), wp = new Waypoint(0, uas->getLongitude(), uas->getLatitude(), uas->getAltitude(),
0.0, true, true, 0.15, 2000); 0.0, true, true, 0.15, 2000);
uas->getWaypointManager().addWaypoint(wp); uas->getWaypointManager().addWaypoint(wp);
} }
if (wp->getFrame() == MAV_FRAME_GLOBAL)
{
emit createWaypointAtMap(QPointF(wp->getX(), wp->getY()));
}
} }
} }
} }

Loading…
Cancel
Save