Browse Source
Also merged MissionController and MissionEditorController into single MissionController implementationQGC4.4
14 changed files with 492 additions and 721 deletions
@ -1,493 +0,0 @@
@@ -1,493 +0,0 @@
|
||||
/*=====================================================================
|
||||
|
||||
QGroundControl Open Source Ground Control Station |
||||
|
||||
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
|
||||
This file is part of the QGROUNDCONTROL project |
||||
|
||||
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
======================================================================*/ |
||||
|
||||
#include "MissionEditorController.h" |
||||
#include "ScreenToolsController.h" |
||||
#include "MultiVehicleManager.h" |
||||
#include "MissionManager.h" |
||||
#include "QGCFileDialog.h" |
||||
#include "CoordinateVector.h" |
||||
#include "QGCMessageBox.h" |
||||
|
||||
#include <QQmlContext> |
||||
#include <QQmlEngine> |
||||
#include <QSettings> |
||||
|
||||
const char* MissionEditorController::_settingsGroup = "MissionEditorController"; |
||||
|
||||
MissionEditorController::MissionEditorController(QObject *parent) |
||||
: QObject(parent) |
||||
, _missionItems(NULL) |
||||
, _canEdit(true) |
||||
, _activeVehicle(NULL) |
||||
, _liveHomePositionAvailable(false) |
||||
, _autoSync(false) |
||||
, _firstMissionItemSync(false) |
||||
, _missionItemsRequested(false) |
||||
{ |
||||
MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance(); |
||||
|
||||
connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionEditorController::_activeVehicleChanged); |
||||
|
||||
Vehicle* activeVehicle = multiVehicleMgr->activeVehicle(); |
||||
if (activeVehicle) { |
||||
_activeVehicleChanged(activeVehicle); |
||||
} else { |
||||
_missionItemsRequested = true; |
||||
_newMissionItemsAvailable(); |
||||
} |
||||
} |
||||
|
||||
MissionEditorController::~MissionEditorController() |
||||
{ |
||||
} |
||||
|
||||
void MissionEditorController::_newMissionItemsAvailable(void) |
||||
{ |
||||
if (_firstMissionItemSync) { |
||||
// This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
|
||||
// to online.
|
||||
|
||||
_firstMissionItemSync = false; |
||||
if (_missionItems && _missionItems->count() > 1) { |
||||
QGCMessageBox::StandardButton button = QGCMessageBox::warning("Mission Editing", |
||||
"The vehicle has sent a new set of Mission Items. " |
||||
"Do you want to discard your current set of unsaved items and use the ones from the vehicle instead?", |
||||
QGCMessageBox::Yes | QGCMessageBox::No, |
||||
QGCMessageBox::No); |
||||
if (button == QGCMessageBox::No) { |
||||
return; |
||||
} |
||||
} |
||||
} else if (!_missionItemsRequested) { |
||||
// We didn't specifically ask for new mission items. Disregard the new set since it is
|
||||
// the most likely the set we just sent to the vehicle.
|
||||
return; |
||||
} |
||||
|
||||
_missionItemsRequested = false; |
||||
|
||||
if (_missionItems) { |
||||
_deinitAllMissionItems(); |
||||
_missionItems->deleteLater(); |
||||
} |
||||
|
||||
MissionManager* missionManager = NULL; |
||||
if (_activeVehicle) { |
||||
missionManager = _activeVehicle->missionManager(); |
||||
} |
||||
|
||||
if (!missionManager || missionManager->inProgress()) { |
||||
_canEdit = true; |
||||
_missionItems = new QmlObjectListModel(this); |
||||
} else { |
||||
_canEdit = missionManager->canEdit(); |
||||
_missionItems = missionManager->copyMissionItems(); |
||||
} |
||||
|
||||
_initAllMissionItems(); |
||||
} |
||||
|
||||
void MissionEditorController::getMissionItems(void) |
||||
{ |
||||
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); |
||||
|
||||
if (activeVehicle) { |
||||
_missionItemsRequested = true; |
||||
MissionManager* missionManager = activeVehicle->missionManager(); |
||||
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditorController::_newMissionItemsAvailable); |
||||
activeVehicle->missionManager()->requestMissionItems(); |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::sendMissionItems(void) |
||||
{ |
||||
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); |
||||
|
||||
if (activeVehicle) { |
||||
activeVehicle->missionManager()->writeMissionItems(*_missionItems, true /* skipFirstItem */); |
||||
_missionItems->setDirty(false); |
||||
} |
||||
} |
||||
|
||||
int MissionEditorController::addMissionItem(QGeoCoordinate coordinate) |
||||
{ |
||||
if (!_canEdit) { |
||||
qWarning() << "addMissionItem called with _canEdit == false"; |
||||
} |
||||
|
||||
// Coordinate will come through without altitude
|
||||
coordinate.setAltitude(MissionItem::defaultAltitude); |
||||
|
||||
MissionItem * newItem = new MissionItem(this, _missionItems->count(), coordinate, MAV_CMD_NAV_WAYPOINT); |
||||
_initMissionItem(newItem); |
||||
if (_missionItems->count() == 1) { |
||||
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF); |
||||
} |
||||
_missionItems->append(newItem); |
||||
|
||||
_recalcAll(); |
||||
|
||||
return _missionItems->count() - 1; |
||||
} |
||||
|
||||
void MissionEditorController::removeMissionItem(int index) |
||||
{ |
||||
if (!_canEdit) { |
||||
qWarning() << "addMissionItem called with _canEdit == false"; |
||||
return; |
||||
} |
||||
|
||||
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index)); |
||||
|
||||
_deinitMissionItem(item); |
||||
|
||||
_recalcAll(); |
||||
|
||||
// Set the new current item
|
||||
|
||||
if (index >= _missionItems->count()) { |
||||
index--; |
||||
} |
||||
for (int i=0; i<_missionItems->count(); i++) { |
||||
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i)); |
||||
item->setIsCurrentItem(i == index); |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::loadMissionFromFile(void) |
||||
{ |
||||
QString errorString; |
||||
QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load"); |
||||
|
||||
if (filename.isEmpty()) { |
||||
return; |
||||
} |
||||
|
||||
if (_missionItems) { |
||||
_deinitAllMissionItems(); |
||||
_missionItems->deleteLater(); |
||||
} |
||||
_missionItems = new QmlObjectListModel(this); |
||||
|
||||
_canEdit = true; |
||||
|
||||
QFile file(filename); |
||||
|
||||
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { |
||||
errorString = file.errorString(); |
||||
} else { |
||||
QTextStream in(&file); |
||||
|
||||
const QStringList& version = in.readLine().split(" "); |
||||
|
||||
if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120")) { |
||||
errorString = "The mission file is not compatible with the current version of QGroundControl."; |
||||
} else { |
||||
while (!in.atEnd()) { |
||||
MissionItem* item = new MissionItem(); |
||||
|
||||
if (item->load(in)) { |
||||
_missionItems->append(item); |
||||
|
||||
if (!item->canEdit()) { |
||||
_canEdit = false; |
||||
} |
||||
} else { |
||||
errorString = "The mission file is corrupted."; |
||||
break; |
||||
} |
||||
} |
||||
} |
||||
|
||||
} |
||||
|
||||
if (!errorString.isEmpty()) { |
||||
_missionItems->clear(); |
||||
} |
||||
|
||||
_initAllMissionItems(); |
||||
} |
||||
|
||||
void MissionEditorController::saveMissionToFile(void) |
||||
{ |
||||
QString errorString; |
||||
QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to"); |
||||
|
||||
if (filename.isEmpty()) { |
||||
return; |
||||
} |
||||
|
||||
QFile file(filename); |
||||
|
||||
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { |
||||
errorString = file.errorString(); |
||||
} else { |
||||
QTextStream out(&file); |
||||
|
||||
out << "QGC WPL 120\r\n"; // Version string
|
||||
|
||||
for (int i=0; i<_missionItems->count(); i++) { |
||||
qobject_cast<MissionItem*>(_missionItems->get(i))->save(out); |
||||
} |
||||
} |
||||
|
||||
_missionItems->setDirty(false); |
||||
} |
||||
|
||||
void MissionEditorController::_recalcWaypointLines(void) |
||||
{ |
||||
bool firstCoordinateItem = true; |
||||
MissionItem* lastCoordinateItem = qobject_cast<MissionItem*>(_missionItems->get(0)); |
||||
|
||||
_waypointLines.clear(); |
||||
|
||||
for (int i=1; i<_missionItems->count(); i++) { |
||||
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i)); |
||||
|
||||
if (item->specifiesCoordinate()) { |
||||
if (firstCoordinateItem) { |
||||
if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) { |
||||
// The first coordinate we hit is a takeoff command so link back to home position
|
||||
_waypointLines.append(new CoordinateVector(qobject_cast<MissionItem*>(_missionItems->get(0))->coordinate(), item->coordinate())); |
||||
} else { |
||||
// First coordiante is not a takeoff command, it does not link backwards to anything
|
||||
} |
||||
firstCoordinateItem = false; |
||||
} else { |
||||
// Subsequent coordinate items link to last coordinate item
|
||||
_waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate())); |
||||
} |
||||
lastCoordinateItem = item; |
||||
} |
||||
} |
||||
|
||||
emit waypointLinesChanged(); |
||||
} |
||||
|
||||
// This will update the sequence numbers to be sequential starting from 0
|
||||
void MissionEditorController::_recalcSequence(void) |
||||
{ |
||||
for (int i=0; i<_missionItems->count(); i++) { |
||||
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i)); |
||||
|
||||
// Setup ascending sequence numbers
|
||||
item->setSequenceNumber(i); |
||||
} |
||||
} |
||||
|
||||
// This will update the child item hierarchy
|
||||
void MissionEditorController::_recalcChildItems(void) |
||||
{ |
||||
MissionItem* currentParentItem = qobject_cast<MissionItem*>(_missionItems->get(0)); |
||||
|
||||
currentParentItem->childItems()->clear(); |
||||
|
||||
for (int i=1; i<_missionItems->count(); i++) { |
||||
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i)); |
||||
|
||||
// Set up non-coordinate item child hierarchy
|
||||
if (item->specifiesCoordinate()) { |
||||
item->childItems()->clear(); |
||||
currentParentItem = item; |
||||
} else { |
||||
currentParentItem->childItems()->append(item); |
||||
} |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::_recalcAll(void) |
||||
{ |
||||
_recalcSequence(); |
||||
_recalcChildItems(); |
||||
_recalcWaypointLines(); |
||||
} |
||||
|
||||
/// Initializes a new set of mission items which may have come from the vehicle or have been loaded from a file
|
||||
void MissionEditorController::_initAllMissionItems(void) |
||||
{ |
||||
// Add the home position item to the front
|
||||
MissionItem* homeItem = new MissionItem(this); |
||||
homeItem->setHomePositionSpecialCase(true); |
||||
homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT); |
||||
_missionItems->insert(0, homeItem); |
||||
|
||||
for (int i=0; i<_missionItems->count(); i++) { |
||||
_initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i))); |
||||
} |
||||
|
||||
_recalcAll(); |
||||
|
||||
emit missionItemsChanged(); |
||||
emit canEditChanged(_canEdit); |
||||
|
||||
_missionItems->setDirty(false); |
||||
|
||||
connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionEditorController::_dirtyChanged); |
||||
} |
||||
|
||||
void MissionEditorController::_deinitAllMissionItems(void) |
||||
{ |
||||
for (int i=0; i<_missionItems->count(); i++) { |
||||
_deinitMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i))); |
||||
} |
||||
|
||||
connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionEditorController::_dirtyChanged); |
||||
} |
||||
|
||||
void MissionEditorController::_initMissionItem(MissionItem* item) |
||||
{ |
||||
_missionItems->setDirty(false); |
||||
|
||||
connect(item, &MissionItem::commandChanged, this, &MissionEditorController::_itemCommandChanged); |
||||
connect(item, &MissionItem::coordinateChanged, this, &MissionEditorController::_itemCoordinateChanged); |
||||
} |
||||
|
||||
void MissionEditorController::_deinitMissionItem(MissionItem* item) |
||||
{ |
||||
disconnect(item, &MissionItem::commandChanged, this, &MissionEditorController::_itemCommandChanged); |
||||
disconnect(item, &MissionItem::coordinateChanged, this, &MissionEditorController::_itemCoordinateChanged); |
||||
} |
||||
|
||||
void MissionEditorController::_itemCoordinateChanged(const QGeoCoordinate& coordinate) |
||||
{ |
||||
Q_UNUSED(coordinate); |
||||
_recalcWaypointLines(); |
||||
} |
||||
|
||||
void MissionEditorController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command) |
||||
{ |
||||
Q_UNUSED(command);; |
||||
_recalcChildItems(); |
||||
_recalcWaypointLines(); |
||||
} |
||||
|
||||
void MissionEditorController::_activeVehicleChanged(Vehicle* activeVehicle) |
||||
{ |
||||
if (_activeVehicle) { |
||||
MissionManager* missionManager = _activeVehicle->missionManager(); |
||||
|
||||
disconnect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditorController::_newMissionItemsAvailable); |
||||
disconnect(missionManager, &MissionManager::inProgressChanged, this, &MissionEditorController::_inProgressChanged); |
||||
disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionEditorController::_activeVehicleHomePositionAvailableChanged); |
||||
disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionEditorController::_activeVehicleHomePositionChanged); |
||||
_activeVehicle = NULL; |
||||
_newMissionItemsAvailable(); |
||||
_activeVehicleHomePositionAvailableChanged(false); |
||||
} |
||||
|
||||
_activeVehicle = activeVehicle; |
||||
|
||||
if (_activeVehicle) { |
||||
MissionManager* missionManager = activeVehicle->missionManager(); |
||||
|
||||
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditorController::_newMissionItemsAvailable); |
||||
connect(missionManager, &MissionManager::inProgressChanged, this, &MissionEditorController::_inProgressChanged); |
||||
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionEditorController::_activeVehicleHomePositionAvailableChanged); |
||||
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionEditorController::_activeVehicleHomePositionChanged); |
||||
|
||||
if (missionManager->inProgress()) { |
||||
// Vehicle is still in process of requesting mission items
|
||||
_firstMissionItemSync = true; |
||||
} else { |
||||
// Vehicle already has mission items
|
||||
_firstMissionItemSync = false; |
||||
} |
||||
|
||||
_missionItemsRequested = true; |
||||
_newMissionItemsAvailable(); |
||||
|
||||
_activeVehicleHomePositionChanged(_activeVehicle->homePosition()); |
||||
_activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable()); |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable) |
||||
{ |
||||
_liveHomePositionAvailable = homePositionAvailable; |
||||
emit liveHomePositionAvailableChanged(_liveHomePositionAvailable); |
||||
} |
||||
|
||||
void MissionEditorController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition) |
||||
{ |
||||
_liveHomePosition = homePosition; |
||||
emit liveHomePositionChanged(_liveHomePosition); |
||||
} |
||||
|
||||
void MissionEditorController::deleteCurrentMissionItem(void) |
||||
{ |
||||
for (int i=0; i<_missionItems->count(); i++) { |
||||
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i)); |
||||
if (item->isCurrentItem() && i != 0) { |
||||
removeMissionItem(i); |
||||
return; |
||||
} |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::setAutoSync(bool autoSync) |
||||
{ |
||||
_autoSync = autoSync; |
||||
emit autoSyncChanged(_autoSync); |
||||
|
||||
if (_autoSync) { |
||||
_dirtyChanged(true); |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::_dirtyChanged(bool dirty) |
||||
{ |
||||
if (dirty && _autoSync) { |
||||
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); |
||||
|
||||
if (activeVehicle && !activeVehicle->armed()) { |
||||
if (_activeVehicle->missionManager()->inProgress()) { |
||||
_queuedSend = true; |
||||
} else { |
||||
_autoSyncSend(); |
||||
} |
||||
} |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::_autoSyncSend(void) |
||||
{ |
||||
qDebug() << "Auto-syncing with vehicle"; |
||||
_queuedSend = false; |
||||
if (_missionItems) { |
||||
sendMissionItems(); |
||||
_missionItems->setDirty(false); |
||||
} |
||||
} |
||||
|
||||
void MissionEditorController::_inProgressChanged(bool inProgress) |
||||
{ |
||||
if (!inProgress && _queuedSend) { |
||||
_autoSyncSend(); |
||||
} |
||||
} |
||||
|
||||
QmlObjectListModel* MissionEditorController::missionItems(void) |
||||
{ |
||||
return _missionItems; |
||||
} |
@ -1,109 +0,0 @@
@@ -1,109 +0,0 @@
|
||||
/*=====================================================================
|
||||
|
||||
QGroundControl Open Source Ground Control Station |
||||
|
||||
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
|
||||
This file is part of the QGROUNDCONTROL project |
||||
|
||||
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
======================================================================*/ |
||||
|
||||
#ifndef MissionEditorController_H |
||||
#define MissionEditorController_H |
||||
|
||||
#include <QObject> |
||||
|
||||
#include "QmlObjectListModel.h" |
||||
#include "Vehicle.h" |
||||
|
||||
class MissionEditorController : public QObject |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
MissionEditorController(QObject* parent = NULL); |
||||
~MissionEditorController(); |
||||
|
||||
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged) |
||||
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) |
||||
Q_PROPERTY(bool canEdit READ canEdit NOTIFY canEditChanged) |
||||
Q_PROPERTY(bool liveHomePositionAvailable READ liveHomePositionAvailable NOTIFY liveHomePositionAvailableChanged) |
||||
Q_PROPERTY(QGeoCoordinate liveHomePosition READ liveHomePosition NOTIFY liveHomePositionChanged) |
||||
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged) |
||||
|
||||
Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate); |
||||
Q_INVOKABLE void getMissionItems(void); |
||||
Q_INVOKABLE void sendMissionItems(void); |
||||
Q_INVOKABLE void loadMissionFromFile(void); |
||||
Q_INVOKABLE void saveMissionToFile(void); |
||||
Q_INVOKABLE void removeMissionItem(int index); |
||||
Q_INVOKABLE void deleteCurrentMissionItem(void); |
||||
|
||||
// Property accessors
|
||||
|
||||
QmlObjectListModel* missionItems(void); |
||||
QmlObjectListModel* waypointLines(void) { return &_waypointLines; } |
||||
bool canEdit(void) { return _canEdit; } |
||||
bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; } |
||||
QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; } |
||||
bool autoSync(void) { return _autoSync; } |
||||
void setAutoSync(bool autoSync); |
||||
|
||||
signals: |
||||
void missionItemsChanged(void); |
||||
void canEditChanged(bool canEdit); |
||||
void waypointLinesChanged(void); |
||||
void liveHomePositionAvailableChanged(bool homePositionAvailable); |
||||
void liveHomePositionChanged(const QGeoCoordinate& homePosition); |
||||
void autoSyncChanged(bool autoSync); |
||||
|
||||
private slots: |
||||
void _newMissionItemsAvailable(); |
||||
void _itemCoordinateChanged(const QGeoCoordinate& coordinate); |
||||
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command); |
||||
void _activeVehicleChanged(Vehicle* activeVehicle); |
||||
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable); |
||||
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition); |
||||
void _dirtyChanged(bool dirty); |
||||
void _inProgressChanged(bool inProgress); |
||||
|
||||
private: |
||||
void _recalcSequence(void); |
||||
void _recalcWaypointLines(void); |
||||
void _recalcChildItems(void); |
||||
void _recalcAll(void); |
||||
void _initAllMissionItems(void); |
||||
void _deinitAllMissionItems(void); |
||||
void _initMissionItem(MissionItem* item); |
||||
void _deinitMissionItem(MissionItem* item); |
||||
void _autoSyncSend(void); |
||||
|
||||
private: |
||||
QmlObjectListModel* _missionItems; |
||||
QmlObjectListModel _waypointLines; |
||||
bool _canEdit; ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save
|
||||
Vehicle* _activeVehicle; |
||||
bool _liveHomePositionAvailable; |
||||
QGeoCoordinate _liveHomePosition; |
||||
bool _autoSync; |
||||
bool _firstMissionItemSync; |
||||
bool _missionItemsRequested; |
||||
bool _queuedSend; |
||||
|
||||
static const char* _settingsGroup; |
||||
}; |
||||
|
||||
#endif |
Loading…
Reference in new issue