Commit 9683bd14 authored by pixhawk's avatar pixhawk

Working WP manager -> map waypoint updates. List reordering does not work yet....

Working WP manager -> map waypoint updates. List reordering does not work yet. Next steps: List reordering, map -> WP manager updates, better waypoint graphs
parent 6a9f84b3
......@@ -188,7 +188,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui \
src/ui/mission/QGCMissionDoWidget.ui \
src/ui/mission/QGCMissionConditionWidget.ui
src/ui/mission/QGCMissionConditionWidget.ui \
src/ui/map/QGCMapToolbar.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -301,7 +302,8 @@ HEADERS += src/MG.h \
src/uas/QGCUASParamManager.h \
src/ui/map/QGCMapWidget.h \
src/ui/map/MAV2DIcon.h \
src/ui/mavlink/QGCMAVLinkTextEdit.h
src/ui/mavlink/QGCMAVLinkTextEdit.h \
src/ui/map/QGCMapToolbar.h
# src/ui/map/Waypoint2DIcon.h \
......@@ -429,7 +431,8 @@ SOURCES += src/main.cc \
src/uas/QGCUASParamManager.cc \
src/ui/map/QGCMapWidget.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/mavlink/QGCMAVLinkTextEdit.cc
src/ui/mavlink/QGCMAVLinkTextEdit.cc \
src/ui/map/QGCMapToolbar.cc
# src/ui/map/Waypoint2DIcon.cc
macx|win32-msvc2008::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
contains(DEPENDENCIES_PRESENT, osg) {
......
......@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1, double _param2, double _param3, double _param4,
bool _autocontinue, bool _current, MAV_FRAME _frame, MAV_CMD _action)
bool _autocontinue, bool _current, MAV_FRAME _frame, MAV_CMD _action, const QString& _description)
: id(_id),
x(_x),
y(_y),
......@@ -48,7 +48,8 @@ Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1,
orbit(_param3),
param1(_param1),
param2(_param2),
name(QString("WP%1").arg(id, 2, 10, QChar('0')))
name(QString("WP%1").arg(id, 2, 10, QChar('0'))),
description(_description)
{
}
......@@ -70,15 +71,15 @@ void Waypoint::save(QTextStream &saveStream)
position = position.arg(z, 0, 'g', 18);
QString parameters("%1\t%2\t%3\t%4");
parameters = parameters.arg(param1, 0, 'g', 18).arg(param2, 0, 'g', 18).arg(orbit, 0, 'g', 18).arg(yaw, 0, 'g', 18);
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE>
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE> <DESCRIPTION>
// as documented here: http://qgroundcontrol.org/waypoint_protocol
saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n";
saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n"; //"\t" << this->getDescription() << "\r\n";
}
bool Waypoint::load(QTextStream &loadStream)
{
const QStringList &wpParams = loadStream.readLine().split("\t");
if (wpParams.size() == 12) {
if (wpParams.size() == 13) {
this->id = wpParams[0].toInt();
this->current = (wpParams[1].toInt() == 1 ? true : false);
this->frame = (MAV_FRAME) wpParams[2].toInt();
......@@ -91,6 +92,7 @@ bool Waypoint::load(QTextStream &loadStream)
this->y = wpParams[9].toDouble();
this->z = wpParams[10].toDouble();
this->autocontinue = (wpParams[11].toInt() == 1 ? true : false);
//this->description = wpParams[12];
return true;
}
return false;
......
......@@ -44,7 +44,7 @@ class Waypoint : public QObject
public:
Waypoint(quint16 id = 0, double x = 0.0, double y = 0.0, double z = 0.0, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0,
bool autocontinue = true, bool current = false, MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT);
bool autocontinue = true, bool current = false, MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT, const QString& description=QString(""));
~Waypoint();
quint16 getId() const {
......@@ -119,6 +119,9 @@ public:
const QString& getName() const {
return name;
}
const QString& getDescription() const {
return description;
}
/** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType();
......@@ -141,6 +144,7 @@ protected:
double param2;
int turns;
QString name;
QString description;
public slots:
void setId(quint16 id);
......
......@@ -294,6 +294,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
Waypoint *t = waypoints[seq];
waypoints.remove(seq);
delete t;
t = NULL;
for(int i = seq; i < waypoints.size(); i++) {
waypoints[i]->setId(i);
......
#include "QGCMapToolbar.h"
#include "ui_QGCMapToolbar.h"
QGCMapToolbar::QGCMapToolbar(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMapToolbar)
{
ui->setupUi(this);
}
QGCMapToolbar::~QGCMapToolbar()
{
delete ui;
}
#ifndef QGCMAPTOOLBAR_H
#define QGCMAPTOOLBAR_H
#include <QWidget>
namespace Ui {
class QGCMapToolbar;
}
class QGCMapToolbar : public QWidget
{
Q_OBJECT
public:
explicit QGCMapToolbar(QWidget *parent = 0);
~QGCMapToolbar();
private:
Ui::QGCMapToolbar *ui;
};
#endif // QGCMAPTOOLBAR_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMapToolbar</class>
<widget class="QWidget" name="QGCMapToolbar">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>617</width>
<height>28</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>2</number>
</property>
<item>
<widget class="QPushButton" name="goToLatLonButton">
<property name="text">
<string>Lat/Lon</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="goToHomeButton">
<property name="text">
<string>Home</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="editButton">
<property name="text">
<string>Edit</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="setHomeButton">
<property name="text">
<string>Set Home</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="latLonLabel">
<property name="text">
<string>Mouse Coordinate</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "QGCMapWidget.h"
#include "QGCMapToolbar.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "MAV2DIcon.h"
#include "UASWaypointManager.h"
QGCMapWidget::QGCMapWidget(QWidget *parent) :
mapcontrol::OPMapWidget(parent)
mapcontrol::OPMapWidget(parent),
currWPManager(NULL)
{
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(updateSelectedSystem(int)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)));
foreach (UASInterface* uas, UASManager::instance()->getUASList())
{
addUAS(uas);
}
internals::PointLatLng pos_lat_lon = internals::PointLatLng(0, 0);
// // **************
......@@ -47,6 +48,7 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
SetShowHome(true); // display the HOME position on the map
SetShowUAV(true); // display the UAV position on the map
//SetShowDiagnostics(true); // Not needed in flight / production mode
Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters)
Home->SetShowSafeArea(true); // show the safe area
......@@ -70,6 +72,15 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
setFrameStyle(QFrame::NoFrame); // no border frame
setBackgroundBrush(QBrush(Qt::black)); // tile background
// Set current home position
updateHomePosition(UASManager::instance()->getHomeLatitude(), UASManager::instance()->getHomeLongitude(), UASManager::instance()->getHomeAltitude());
// Set currently selected system
activeUASSet(UASManager::instance()->getActiveUAS());
// FIXME XXX this is a hack to trick OPs current 1-system design
SetShowUAV(false);
setFocus();
}
......@@ -91,6 +102,41 @@ void QGCMapWidget::addUAS(UASInterface* uas)
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;
// Disconnect old MAV manager
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*)));
disconnect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypoint(Waypoint*)));
}
if (uas) {
currWPManager = uas->getWaypointManager();
// QColor color = mav->getColor();
// color.setAlphaF(0.9);
// QPen* pen = new QPen(color);
// pen->setWidth(3.0);
// mavPens.insert(mav->getUASID(), pen);
// // FIXME Remove after refactoring
// waypointPath->setPen(pen);
// 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*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypoint(Waypoint*)));
updateSelectedSystem(uas->getUASID());
}
}
/**
* Updates the global position of one MAV and append the last movement to the trail
*
......@@ -118,78 +164,8 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo
// Set new lat/lon position of UAV icon
internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
uav->SetUAVPos(pos_lat_lon, alt);
// Convert from radians to degrees and apply
uav->SetUAVHeading((uas->getYaw()/M_PI)*180.0f);
// static int uasid = 220;
// if (uas->getUASID() == uasid)
// {
// internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
// UAV->SetUAVPos(pos_lat_lon, alt);
// if (!UAV->isVisible()) UAV->show();
// qDebug() << "Updating 2D map position" << uas->getUASID() << "LAT:" << lat << "LON:" << lon;
// }
// QPointF coordinate;
// coordinate.setX(lon);
// coordinate.setY(lat);
// if (!uasIcons.contains(uas->getUASID())) {
// // Get the UAS color
// QColor uasColor = uas->getColor();
// // Icon
// //QPen* pointpen = new QPen(uasColor);
// qDebug() << "2D MAP: ADDING" << uas->getUASName() << __FILE__ << __LINE__;
// p = new MAV2DIcon(uas, 68, uas->getSystemType(), uas->getColor(), QString("%1").arg(uas->getUASID()), qmapcontrol::Point::Middle);
// uasIcons.insert(uas->getUASID(), p);
// mc->layer("Waypoints")->addGeometry(p);
// // Line
// // A QPen also can use transparency
// // QList<qmapcontrol::Point*> points;
// // points.append(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
// // QPen* linepen = new QPen(uasColor.darker());
// // linepen->setWidth(2);
// // // Create tracking line string
// // qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, QString("%1").arg(uas->getUASID()), linepen);
// // uasTrails.insert(uas->getUASID(), ls);
// // // Add the LineString to the layer
// // mc->layer("Waypoints")->addGeometry(ls);
// } else {
// // p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
// // if (p)
// // {
// p = uasIcons.value(uas->getUASID());
// p->setCoordinate(QPointF(lon, lat));
// //p->setYaw(uas->getYaw());
// // }
// // Extend trail
// // uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
// }
// if (isVisible()) mc->updateRequest(p->boundingBox().toRect());
// //if (isVisible()) mc->updateRequestNew();//(uasTrails.value(uas->getUASID())->boundingBox().toRect());
// if (this->mav && uas->getUASID() == this->mav->getUASID()) {
// // Limit the position update rate
// quint64 currTime = MG::TIME::getGroundTimeNow();
// if (currTime - lastUpdate > 120) {
// lastUpdate = currTime;
// // Sets the view to the interesting area
// if (followgps->isChecked()) {
// updatePosition(0, lon, lat);
// } else {
// // Refresh the screen
// //if (isVisible()) mc->updateRequestNew();
// }
// }
// }
}
......@@ -208,7 +184,7 @@ void QGCMapWidget::updateSystemSpecs(int uas)
}
/**
* Does not update the system type or configuration, only the current state.
* Does not update the system type or configuration, only the selected status
*/
void QGCMapWidget::updateSelectedSystem(int uas)
{
......@@ -223,29 +199,192 @@ void QGCMapWidget::updateSelectedSystem(int uas)
}
}
///**
// * Updates all UAVs at once
// */
//void QGCMapWidget::updateUAVs()
//{
//}
// MAP NAVIGATION
void QGCMapWidget::showGoToDialog()
{
bool ok;
QString text = QInputDialog::getText(this, tr("Please enter coordinates"),
tr("Coordinates (Lat,Lon):"), QLineEdit::Normal,
QString("%1,%2").arg(CurrentPosition().Lat()).arg( CurrentPosition().Lng()), &ok);
if (ok && !text.isEmpty()) {
QStringList split = text.split(",");
if (split.length() == 2) {
bool convert;
double latitude = split.first().toDouble(&convert);
ok &= convert;
double longitude = split.last().toDouble(&convert);
ok &= convert;
if (ok) {
internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude);
SetCurrentPosition(pos_lat_lon); // set the map position
}
}
}
}
void QGCMapWidget::updateHomePosition(double latitude, double longitude, double altitude)
{
Home->SetCoord(internals::PointLatLng(latitude, longitude));
Home->SetAltitude(altitude);
SetShowHome(true); // display the HOME position on the map
}
// WAYPOINT UPDATE FUNCTIONS
/**
* Updates the attitude
* This function is called if a a single waypoint is updated and
* also if the whole list changes.
*/
void QGCMapWidget::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec)
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
{
// Q_UNUSED(roll);
// Q_UNUSED(pitch);
// Q_UNUSED(usec);
// if (mc) {
// if (uas) {
// MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID(), NULL));
// if (icon) {
// icon->setYaw(yaw);
// 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.
if (UASManager::instance()->getUASForId(uas)->getWaypointManager() == currWPManager) {
// Only accept waypoints in global coordinate frame
if (wp->getFrame() == MAV_FRAME_GLOBAL && wp->isNavigationType()) {
// We're good, this is a global waypoint
// Get the index of this waypoint
// note the call to getGlobalFrameAndNavTypeIndexOf()
// 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) return;
// Check if wp exists yet in map
if (!waypointsToIcons.contains(wp)) {
// Create icon for new WP
mapcontrol::WayPointItem* icon = WPCreate(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()), wp->getAltitude(), wp->getDescription());
icon->SetHeading(wp->getYaw());
// Update maps to allow inverse data association
waypointsToIcons.insert(wp, icon);
iconsToWaypoints.insert(icon, wp);
} else {
// Waypoint exists, block it's signals and update it
mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
// Make sure we don't die on a null pointer
// this should never happen, just a precaution
if (!icon) return;
// Block outgoing signals to prevent an infinite signal loop
// should not happen, just a precaution
this->blockSignals(true);
// Update the WP
icon->SetCoord(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()));
icon->SetAltitude(wp->getAltitude());
icon->SetHeading(wp->getYaw());
icon->SetNumber(wp->getId());
// Re-enable signals again
this->blockSignals(false);
}
} else {
// Check if the index of this waypoint is larger than the global
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
if (waypointsToIcons.size() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameAndNavTypeCount()) {
updateWaypointList(uas);
}
}
}
}
/**
* Update the whole list of waypoints. This is e.g. necessary if the list order changed.
* The UAS manager will emit the appropriate signal whenever updating the list
* is necessary.
*/
void QGCMapWidget::updateWaypointList(int 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.
if (UASManager::instance()->getUASForId(uas)->getWaypointManager() == currWPManager) {
qDebug() << "UPDATING WP LIST";
// Get current WP list
// compare to local WP maps and
// update / remove all WPs
// int localCount = waypointsToIcons.count();
// ORDER MATTERS HERE!
// TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
// Delete first all old waypoints
// this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
QVector<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
foreach (Waypoint* wp, waypointsToIcons.keys())
{
// Get icon to work on
mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
if (!wps.contains(wp))
{
waypointsToIcons.remove(wp);
iconsToWaypoints.remove(icon);
delete icon;
icon = NULL;
}
}
// Update all existing waypoints
foreach (Waypoint* wp, waypointsToIcons.keys())
{
// Update remaining waypoints
updateWaypoint(uas, wp);
}
// Update all potentially new waypoints
foreach (Waypoint* wp, wps)
{
// Update / add only if new
if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
}
// int globalCount = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeCount();
// // Get already existing waypoints
// UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
// if (uasInstance) {
// // Get update rect of old content, this is what will be redrawn
// // in the last step
// QRect updateRect = waypointPath->boundingBox().toRect();
// // Get all waypoints, including non-global waypoints
// QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getWaypointList();
// // Clear if necessary
// if (wpList.count() == 0) {
// clearWaypoints(uas);
// return;
// }
// // Trim internal list to number of global waypoints in the waypoint manager list
// int overSize = waypointPath->points().count() - uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeCount();
// if (overSize > 0) {
// // Remove n waypoints at the end of the list
// // the remaining waypoints will be updated
// // in the next step
// for (int i = 0; i < overSize; ++i) {
// wps.removeLast();
// mc->layer("Waypoints")->removeGeometry(wpIcons.last());
// wpIcons.removeLast();
// waypointPath->points().removeLast();
// }
// }
// // Load all existing waypoints into map view
// foreach (Waypoint* wp, wpList) {
// // Block map draw updates, since we update everything in the next step
// // but update internal data structures.
// // Please note that updateWaypoint() ignores non-global waypoints
// updateWaypoint(mav->getUASID(), wp, false);
// }
// // Update view
// if (isVisible()) mc->updateRequest(updateRect);
// }
// }
}
}
#ifndef QGCMAPWIDGET_H
#define QGCMAPWIDGET_H
#include <QMap>
#include "opmapcontrol.h"
class UASInterface;
class UASWaypointManager;
class Waypoint;
/**
* @brief Class representing a 2D map using aerial imagery
*/
class QGCMapWidget : public mapcontrol::OPMapWidget
{
Q_OBJECT
......@@ -13,18 +19,43 @@ public:
~QGCMapWidget();
signals:
void homePositionChanged(double latitude, double longitude, double altitude);
public slots:
/** @brief Add system to map view */
void addUAS(UASInterface* uas);
/** @brief Update the global position of a system */
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
/** @brief Update the type, size, etc. of this system */
void updateSystemSpecs(int uas);
/** @brief Update the whole system state */
void updateSelectedSystem(int uas);
/** @brief Change current system in focus / editing */
void activeUASSet(UASInterface* uas);
/** @brief Show a dialog to jump to given GPS coordinates */
void showGoToDialog();
/** @brief Update this waypoint for this UAS */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief Update the whole waypoint */
void updateWaypointList(int uas);
/** @brief Update the home position on the map */
void updateHomePosition(double latitude, double longitude, double altitude);
protected:
/** @brief Update the attitude of this system */
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec);
/** @brief Update the highlighting of the currently controlled system */
void updateSelectedSystem(int uas);
/** @brief Set the current mouse position on the map as new home position */
UASWaypointManager* currWPManager; ///< The current waypoint manager
QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons;
QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints;
// enum editMode {
// NONE,
// WAYPOINTS,
// SWEEP,
// UAVS,
// HOME,
// SAFE_AREA
// };
// enum editMode currEditMode; ///< The current edit mode on the map
};
......
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