Browse Source

Merge pull request #4455 from DonLakeFlyer/MissionAutoLoad

Mission auto load
QGC4.4
Don Gagne 8 years ago committed by GitHub
parent
commit
bd11543d05
  1. 1
      qgroundcontrol.qrc
  2. 8
      src/FlightDisplay/MultiVehicleList.qml
  3. 2
      src/MissionManager/GeoFenceController.cc
  4. 138
      src/MissionManager/MissionController.cc
  5. 25
      src/MissionManager/MissionController.h
  6. 193
      src/MissionManager/MissionLoader.h
  7. 2
      src/MissionManager/RallyPointController.cc
  8. 66
      src/QmlControls/FlightModeMenu.qml
  9. 1
      src/QmlControls/QGroundControl.Controls.qmldir
  10. 13
      src/QmlControls/QGroundControlQmlGlobal.cc
  11. 10
      src/QmlControls/QGroundControlQmlGlobal.h
  12. 21
      src/Vehicle/Vehicle.cc
  13. 27
      src/ui/preferences/GeneralSettings.qml

1
qgroundcontrol.qrc

@ -48,6 +48,7 @@
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file> <file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
<file alias="QGroundControl/Controls/FactSliderPanel.qml">src/QmlControls/FactSliderPanel.qml</file> <file alias="QGroundControl/Controls/FactSliderPanel.qml">src/QmlControls/FactSliderPanel.qml</file>
<file alias="QGroundControl/Controls/FlightModeDropdown.qml">src/QmlControls/FlightModeDropdown.qml</file> <file alias="QGroundControl/Controls/FlightModeDropdown.qml">src/QmlControls/FlightModeDropdown.qml</file>
<file alias="QGroundControl/Controls/FlightModeMenu.qml">src/QmlControls/FlightModeMenu.qml</file>
<file alias="QGroundControl/Controls/GuidedBar.qml">src/QmlControls/GuidedBar.qml</file> <file alias="QGroundControl/Controls/GuidedBar.qml">src/QmlControls/GuidedBar.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file> <file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file> <file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>

8
src/FlightDisplay/MultiVehicleList.qml

@ -77,10 +77,10 @@ QGCListView {
color: _textColor color: _textColor
} }
QGCLabel { FlightModeMenu {
text: _vehicle.flightMode font.pointSize: ScreenTools.largeFontPointSize
font.pointSize: ScreenTools.largeFontPointSize color: _textColor
color: _textColor activeVehicle: _vehicle
} }
} }

2
src/MissionManager/GeoFenceController.cc

@ -214,7 +214,7 @@ void GeoFenceController::loadFromFile(const QString& filename)
QFile file(filename); QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
errorString = file.errorString(); errorString = file.errorString() + QStringLiteral(" ") + filename;
} else { } else {
QJsonDocument jsonDoc; QJsonDocument jsonDoc;
QByteArray bytes = file.readAll(); QByteArray bytes = file.readAll();

138
src/MissionManager/MissionController.cc

@ -87,7 +87,7 @@ void MissionController::_init(void)
{ {
// We start with an empty mission // We start with an empty mission
_visualItems = new QmlObjectListModel(this); _visualItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_visualItems, false /* addToCenter */); _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
_initAllVisualItems(); _initAllVisualItems();
} }
@ -113,11 +113,11 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void)
_deinitAllVisualItems(); _deinitAllVisualItems();
_visualItems->deleteListAndContents(); _visualItems->deleteLater();
_visualItems = newControllerMissionItems; _visualItems = newControllerMissionItems;
if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) { if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
_addPlannedHomePosition(_visualItems,true /* addToCenter */); _addPlannedHomePosition(_activeVehicle, _visualItems,true /* addToCenter */);
} }
_missionItemsRequested = false; _missionItemsRequested = false;
@ -139,12 +139,18 @@ void MissionController::loadFromVehicle(void)
void MissionController::sendToVehicle(void) void MissionController::sendToVehicle(void)
{ {
if (_activeVehicle) { sendItemsToVehicle(_activeVehicle, _visualItems);
_visualItems->setDirty(false);
}
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
if (vehicle) {
// Convert to MissionItems so we can send to vehicle // Convert to MissionItems so we can send to vehicle
QList<MissionItem*> missionItems; QList<MissionItem*> missionItems;
for (int i=0; i<_visualItems->count(); i++) { for (int i=0; i<visualMissionItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i)); VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));
if (visualItem->isSimpleItem()) { if (visualItem->isSimpleItem()) {
missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem())); missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
} else { } else {
@ -153,15 +159,14 @@ void MissionController::sendToVehicle(void)
for (int j=0; j<complexMissionItems->count(); j++) { for (int j=0; j<complexMissionItems->count(); j++) {
missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j)))); missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
} }
delete complexMissionItems; complexMissionItems->deleteLater();
} }
} }
_activeVehicle->missionManager()->writeMissionItems(missionItems); vehicle->missionManager()->writeMissionItems(missionItems);
_visualItems->setDirty(false);
for (int i=0; i<missionItems.count(); i++) { for (int i=0; i<missionItems.count(); i++) {
delete missionItems[i]; missionItems[i]->deleteLater();
} }
} }
} }
@ -216,7 +221,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i) int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{ {
int sequenceNumber = _nextSequenceNumber(); int sequenceNumber = _nextSequenceNumber();
SurveyMissionItem* newItem = new SurveyMissionItem(_activeVehicle, this); SurveyMissionItem* newItem = new SurveyMissionItem(_activeVehicle, _visualItems);
newItem->setSequenceNumber(sequenceNumber); newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate); newItem->setCoordinate(coordinate);
_initVisualItem(newItem); _initVisualItem(newItem);
@ -260,15 +265,15 @@ void MissionController::removeAll(void)
{ {
if (_visualItems) { if (_visualItems) {
_deinitAllVisualItems(); _deinitAllVisualItems();
_visualItems->deleteListAndContents(); _visualItems->deleteLater();
_visualItems = new QmlObjectListModel(this); _visualItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_visualItems, false /* addToCenter */); _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
_initAllVisualItems(); _initAllVisualItems();
_visualItems->setDirty(true); _visualItems->setDirty(true);
} }
} }
bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString) bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
{ {
QJsonParseError jsonParseError; QJsonParseError jsonParseError;
QJsonDocument jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError)); QJsonDocument jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));
@ -295,13 +300,13 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
} }
if (fileVersion == 1) { if (fileVersion == 1) {
return _loadJsonMissionFileV1(json, visualItems, complexItems, errorString); return _loadJsonMissionFileV1(vehicle, json, visualItems, complexItems, errorString);
} else { } else {
return _loadJsonMissionFileV2(json, visualItems, complexItems, errorString); return _loadJsonMissionFileV2(vehicle, json, visualItems, complexItems, errorString);
} }
} }
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString) bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
{ {
// Validate root object keys // Validate root object keys
QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = { QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
@ -325,7 +330,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return false; return false;
} }
SurveyMissionItem* item = new SurveyMissionItem(_activeVehicle, this); SurveyMissionItem* item = new SurveyMissionItem(vehicle, visualItems);
const QJsonObject itemObject = itemValue.toObject(); const QJsonObject itemObject = itemValue.toObject();
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
complexItems->append(item); complexItems->append(item);
@ -368,7 +373,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
} }
const QJsonObject itemObject = itemValue.toObject(); const QJsonObject itemObject = itemValue.toObject();
SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber(); qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
visualItems->append(item); visualItems->append(item);
@ -381,7 +386,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
} while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count()); } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
if (json.contains(_jsonPlannedHomePositionKey)) { if (json.contains(_jsonPlannedHomePositionKey)) {
SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) { if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
visualItems->insert(0, item); visualItems->insert(0, item);
@ -389,13 +394,13 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return false; return false;
} }
} else { } else {
_addPlannedHomePosition(visualItems, true /* addToCenter */); _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
} }
return true; return true;
} }
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString) bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
{ {
// Validate root object keys // Validate root object keys
QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = { QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
@ -417,7 +422,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) { if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
return false; return false;
} }
if (json.contains(_jsonVehicleTypeKey) && _activeVehicle->isOfflineEditingVehicle()) { if (json.contains(_jsonVehicleTypeKey) && vehicle->isOfflineEditingVehicle()) {
QGroundControlQmlGlobal::offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble()); QGroundControlQmlGlobal::offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
} }
if (json.contains(_jsonCruiseSpeedKey)) { if (json.contains(_jsonCruiseSpeedKey)) {
@ -427,7 +432,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
QGroundControlQmlGlobal::offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble()); QGroundControlQmlGlobal::offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
} }
SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
homeItem->setCoordinate(homeCoordinate); homeItem->setCoordinate(homeCoordinate);
visualItems->insert(0, homeItem); visualItems->insert(0, homeItem);
qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate; qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
@ -457,7 +462,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) { if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
qCDebug(MissionControllerLog) << "Loading MISSION_ITEM: nextSequenceNumber" << nextSequenceNumber; qCDebug(MissionControllerLog) << "Loading MISSION_ITEM: nextSequenceNumber" << nextSequenceNumber;
SimpleMissionItem* simpleItem = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems);
if (simpleItem->load(itemObject, nextSequenceNumber++, errorString)) { if (simpleItem->load(itemObject, nextSequenceNumber++, errorString)) {
visualItems->append(simpleItem); visualItems->append(simpleItem);
} else { } else {
@ -474,7 +479,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) { if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber; qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
SurveyMissionItem* surveyItem = new SurveyMissionItem(_activeVehicle, this); SurveyMissionItem* surveyItem = new SurveyMissionItem(vehicle, visualItems);
if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) { if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false; return false;
} }
@ -519,7 +524,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
return true; return true;
} }
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString) bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
{ {
bool addPlannedHomePosition = false; bool addPlannedHomePosition = false;
@ -540,7 +545,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
if (versionOk) { if (versionOk) {
while (!stream.atEnd()) { while (!stream.atEnd()) {
SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
if (item->load(stream)) { if (item->load(stream)) {
visualItems->append(item); visualItems->append(item);
@ -555,7 +560,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
} }
if (addPlannedHomePosition || visualItems->count() == 0) { if (addPlannedHomePosition || visualItems->count() == 0) {
_addPlannedHomePosition(visualItems, true /* addToCenter */); _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
// Update sequence numbers in DO_JUMP commands to take into account added home position in index 0 // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
for (int i=1; i<visualItems->count(); i++) { for (int i=1; i<visualItems->count(); i++) {
@ -571,19 +576,49 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
void MissionController::loadFromFile(const QString& filename) void MissionController::loadFromFile(const QString& filename)
{ {
QmlObjectListModel* newVisualItems = NULL;
QmlObjectListModel* newComplexItems = NULL;
if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems, &newComplexItems)) {
return;
}
if (_visualItems) {
_deinitAllVisualItems();
_visualItems->deleteLater();
}
if (_complexItems) {
_complexItems->deleteLater();
}
_visualItems = newVisualItems;
_complexItems = newComplexItems;
if (_visualItems->count() == 0) {
_addPlannedHomePosition(_activeVehicle, _visualItems, true /* addToCenter */);
}
_initAllVisualItems();
}
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems)
{
*visualItems = NULL;
*complexItems = NULL;
QString errorString; QString errorString;
if (filename.isEmpty()) { if (filename.isEmpty()) {
return; return false;
} }
QmlObjectListModel* newVisualItems = new QmlObjectListModel(this); *visualItems = new QmlObjectListModel();
QmlObjectListModel* newComplexItems = new QmlObjectListModel(this); *complexItems = new QmlObjectListModel();
QFile file(filename); QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
errorString = file.errorString(); errorString = file.errorString() + QStringLiteral(" ") + filename;
} else { } else {
QByteArray bytes = file.readAll(); QByteArray bytes = file.readAll();
QTextStream stream(&bytes); QTextStream stream(&bytes);
@ -591,42 +626,21 @@ void MissionController::loadFromFile(const QString& filename)
QString firstLine = stream.readLine(); QString firstLine = stream.readLine();
if (firstLine.contains(QRegExp("QGC.*WPL"))) { if (firstLine.contains(QRegExp("QGC.*WPL"))) {
stream.seek(0); stream.seek(0);
_loadTextMissionFile(stream, newVisualItems, errorString); _loadTextMissionFile(vehicle, stream, *visualItems, errorString);
} else { } else {
_loadJsonMissionFile(bytes, newVisualItems, newComplexItems, errorString); _loadJsonMissionFile(vehicle, bytes, *visualItems, *complexItems, errorString);
} }
} }
if (!errorString.isEmpty()) { if (!errorString.isEmpty()) {
for (int i=0; i<newVisualItems->count(); i++) { (*visualItems)->deleteLater();
newVisualItems->get(i)->deleteLater(); (*complexItems)->deleteLater();
}
for (int i=0; i<newComplexItems->count(); i++) {
newComplexItems->get(i)->deleteLater();
}
delete newVisualItems;
delete newComplexItems;
qgcApp()->showMessage(errorString); qgcApp()->showMessage(errorString);
return; return false;
}
if (_visualItems) {
_deinitAllVisualItems();
_visualItems->deleteListAndContents();
}
if (_complexItems) {
_complexItems->deleteLater();
}
_visualItems = newVisualItems;
_complexItems = newComplexItems;
if (_visualItems->count() == 0) {
_addPlannedHomePosition(_visualItems, true /* addToCenter */);
} }
_initAllVisualItems(); return true;
} }
void MissionController::loadFromFilePicker(void) void MissionController::loadFromFilePicker(void)
@ -1394,11 +1408,11 @@ double MissionController::_normalizeLon(double lon)
} }
/// Add the home position item to the front of the list /// Add the home position item to the front of the list
void MissionController::_addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter) void MissionController::_addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
{ {
bool homePositionSet = false; bool homePositionSet = false;
SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
visualItems->insert(0, homeItem); visualItems->insert(0, homeItem);
if (visualItems->count() > 1 && addToCenter) { if (visualItems->count() > 1 && addToCenter) {

25
src/MissionManager/MissionController.h

@ -59,6 +59,17 @@ public:
/// @return Sequence number for new item /// @return Sequence number for new item
Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i); Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i);
/// Loads the mission items from the specified file
/// @param[in] vehicle Vehicle we are loading items for
/// @param[in] filename File to load from
/// @param[out] visualItems Visual items loaded, returns NULL if error
/// @param[out] complexItems Complex items loaded, returns NULL if error
/// @return success/fail
static bool loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems);
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
// Overrides from PlanElementController // Overrides from PlanElementController
void start (bool editMode) final; void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final; void startStaticActiveVehicle (Vehicle* vehicle) final;
@ -135,13 +146,13 @@ private:
static double _calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem); static double _calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem);
bool _findLastAltitude(double* lastAltitude, MAV_FRAME* frame); bool _findLastAltitude(double* lastAltitude, MAV_FRAME* frame);
bool _findLastAcceptanceRadius(double* lastAcceptanceRadius); bool _findLastAcceptanceRadius(double* lastAcceptanceRadius);
void _addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter); static double _normalizeLat(double lat);
double _normalizeLat(double lat); static double _normalizeLon(double lon);
double _normalizeLon(double lon); static void _addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString); static bool _loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString); static bool _loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString); static bool _loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString); static bool _loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
int _nextSequenceNumber(void); int _nextSequenceNumber(void);
void _setMissionDistance(double missionDistance); void _setMissionDistance(double missionDistance);
void _setMissionTime(double missionTime); void _setMissionTime(double missionTime);

193
src/MissionManager/MissionLoader.h

@ -0,0 +1,193 @@
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#ifndef MissionController_H
#define MissionController_H
#include "PlanElementController.h"
#include "QmlObjectListModel.h"
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "VisualMissionItem.h"
#include <QHash>
class CoordinateVector;
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
typedef QPair<VisualMissionItem*,VisualMissionItem*> VisualItemPair;
typedef QHash<VisualItemPair, CoordinateVector*> CoordVectHashTable;
class MissionController : public PlanElementController
{
Q_OBJECT
public:
MissionController(QObject* parent = NULL);
~MissionController();
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged)
Q_PROPERTY(double missionTime READ missionTime NOTIFY missionTimeChanged)
Q_PROPERTY(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged)
Q_PROPERTY(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged)
Q_PROPERTY(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged)
Q_PROPERTY(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged)
Q_PROPERTY(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged)
Q_INVOKABLE void removeMissionItem(int index);
/// Add a new simple mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int i);
/// Add a new complex mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i);
// Overrides from PlanElementController
void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFilePicker (void) final;
void loadFromFile (const QString& filename) final;
void saveToFilePicker (void) final;
void saveToFile (const QString& filename) final;
void removeAll (void) final;
bool syncInProgress (void) const final;
bool dirty (void) const final;
void setDirty (bool dirty) final;
QString fileExtension(void) const final;
// Property accessors
QGeoCoordinate plannedHomePosition (void);
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* complexVisualItems (void) { return _complexItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
double missionDistance (void) const { return _missionDistance; }
double missionTime (void) const { return _missionTime; }
double missionHoverDistance (void) const { return _missionHoverDistance; }
double missionHoverTime (void) const { return _missionHoverTime; }
double missionCruiseDistance (void) const { return _missionCruiseDistance; }
double missionCruiseTime (void) const { return _missionCruiseTime; }
double missionMaxTelemetry (void) const { return _missionMaxTelemetry; }
double cruiseSpeed (void) const;
double hoverSpeed (void) const;
static void createVisualItemsFromFile(const QString& filename);
signals:
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
void visualItemsChanged(void);
void complexVisualItemsChanged(void);
void waypointLinesChanged(void);
void newItemsFromVehicle(void);
void missionDistanceChanged(double missionDistance);
void missionTimeChanged(void);
void missionHoverDistanceChanged(double missionHoverDistance);
void missionHoverTimeChanged(void);
void missionCruiseDistanceChanged(double missionCruiseDistance);
void missionCruiseTimeChanged(void);
void missionMaxTelemetryChanged(double missionMaxTelemetry);
void cruiseDistanceChanged(double cruiseDistance);
void hoverDistanceChanged(double hoverDistance);
void cruiseSpeedChanged(double cruiseSpeed);
void hoverSpeedChanged(double hoverSpeed);
private slots:
void _newMissionItemsAvailableFromVehicle();
void _itemCommandChanged(void);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
void _inProgressChanged(bool inProgress);
void _currentMissionItemChanged(int sequenceNumber);
void _recalcWaypointLines(void);
void _recalcAltitudeRangeBearing(void);
void _homeCoordinateChanged(void);
private:
void _init(void);
void _recalcSequence(void);
void _recalcChildItems(void);
void _recalcAll(void);
void _initAllVisualItems(void);
void _deinitAllVisualItems(void);
void _initVisualItem(VisualMissionItem* item);
void _deinitVisualItem(VisualMissionItem* item);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
static void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
static double _calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem);
bool _findLastAltitude(double* lastAltitude, MAV_FRAME* frame);
bool _findLastAcceptanceRadius(double* lastAcceptanceRadius);
void _addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter);
double _normalizeLat(double lat);
double _normalizeLon(double lon);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
int _nextSequenceNumber(void);
void _setMissionDistance(double missionDistance);
void _setMissionTime(double missionTime);
void _setMissionHoverDistance(double missionHoverDistance);
void _setMissionHoverTime(double missionHoverTime);
void _setMissionCruiseDistance(double missionCruiseDistance);
void _setMissionCruiseTime(double missionCruiseTime);
void _setMissionMaxTelemetry(double missionMaxTelemetry);
// Overrides from PlanElementController
void _activeVehicleBeingRemoved(void) final;
void _activeVehicleSet(void) final;
private:
QmlObjectListModel* _visualItems;
QmlObjectListModel* _complexItems;
QmlObjectListModel _waypointLines;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _missionItemsRequested;
bool _queuedSend;
double _missionDistance;
double _missionTime;
double _missionHoverDistance;
double _missionHoverTime;
double _missionCruiseDistance;
double _missionCruiseTime;
double _missionMaxTelemetry;
static const char* _settingsGroup;
static const char* _jsonFileTypeValue;
static const char* _jsonFirmwareTypeKey;
static const char* _jsonVehicleTypeKey;
static const char* _jsonCruiseSpeedKey;
static const char* _jsonHoverSpeedKey;
static const char* _jsonItemsKey;
static const char* _jsonPlannedHomePositionKey;
static const char* _jsonParamsKey;
// Deprecated V1 format keys
static const char* _jsonMavAutopilotKey;
static const char* _jsonComplexItemsKey;
static const int _missionFileVersion;
};
#endif

2
src/MissionManager/RallyPointController.cc

@ -111,7 +111,7 @@ void RallyPointController::loadFromFile(const QString& filename)
QFile file(filename); QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
errorString = file.errorString(); errorString = file.errorString() + QStringLiteral(" ") + filename;
} else { } else {
QJsonDocument jsonDoc; QJsonDocument jsonDoc;
QByteArray bytes = file.readAll(); QByteArray bytes = file.readAll();

66
src/QmlControls/FlightModeMenu.qml

@ -0,0 +1,66 @@
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.5
import QtQuick.Controls 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
// Label control whichs pop up a flight mode change menu when clicked
QGCLabel {
id: flightModeMenuLabel
text: activeVehicle ? activeVehicle.flightMode : qsTr("N/A", "No data to display")
property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
Menu {
id: flightModesMenu
}
Component {
id: flightModeMenuItemComponent
MenuItem {
onTriggered: activeVehicle.flightMode = text
}
}
property var flightModesMenuItems: []
function updateFlightModesMenu() {
if (activeVehicle && activeVehicle.flightModeSetAvailable) {
// Remove old menu items
for (var i = 0; i < flightModesMenuItems.length; i++) {
flightModesMenu.removeItem(flightModesMenuItems[i])
}
flightModesMenuItems.length = 0
// Add new items
for (var i = 0; i < activeVehicle.flightModes.length; i++) {
var menuItem = flightModeMenuItemComponent.createObject(null, { "text": activeVehicle.flightModes[i] })
flightModesMenuItems.push(menuItem)
flightModesMenu.insertItem(i, menuItem)
}
}
}
Component.onCompleted: flightModeMenuLabel.updateFlightModesMenu()
Connections {
target: QGroundControl.multiVehicleManager
onActiveVehicleChanged: flightModeMenuLabel.updateFlightModesMenu()
}
MouseArea {
visible: activeVehicle && activeVehicle.flightModeSetAvailable
anchors.fill: parent
onClicked: flightModesMenu.popup()
}
}

1
src/QmlControls/QGroundControl.Controls.qmldir

@ -7,6 +7,7 @@ DropButton 1.0 DropButton.qml
ExclusiveGroupItem 1.0 ExclusiveGroupItem.qml ExclusiveGroupItem 1.0 ExclusiveGroupItem.qml
FactSliderPanel 1.0 FactSliderPanel.qml FactSliderPanel 1.0 FactSliderPanel.qml
FlightModeDropdown 1.0 FlightModeDropdown.qml FlightModeDropdown 1.0 FlightModeDropdown.qml
FlightModeMenu 1.0 FlightModeMenu.qml
GuidedBar 1.0 GuidedBar.qml GuidedBar 1.0 GuidedBar.qml
IndicatorButton 1.0 IndicatorButton.qml IndicatorButton 1.0 IndicatorButton.qml
JoystickThumbPad 1.0 JoystickThumbPad.qml JoystickThumbPad 1.0 JoystickThumbPad.qml

13
src/QmlControls/QGroundControlQmlGlobal.cc

@ -33,6 +33,7 @@ SettingsFact* QGroundControlQmlGlobal::_batteryPercentRemainingAnnounceFact =
const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick"; const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick";
const char* QGroundControlQmlGlobal::_baseFontPointSizeKey = "BaseDeviceFontPointSize"; const char* QGroundControlQmlGlobal::_baseFontPointSizeKey = "BaseDeviceFontPointSize";
const char* QGroundControlQmlGlobal::_missionAutoLoadDirKey = "MissionAutoLoadDir";
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app) QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
: QGCTool(app) : QGCTool(app)
@ -353,3 +354,15 @@ QMap<QString, FactMetaData*>& QGroundControlQmlGlobal::nameToMetaDataMap(void) {
return map; return map;
} }
QString QGroundControlQmlGlobal::missionAutoLoadDir(void)
{
QSettings settings;
return settings.value(_missionAutoLoadDirKey).toString();
}
void QGroundControlQmlGlobal::setMissionAutoLoadDir(const QString& missionAutoLoadDir)
{
QSettings settings;
settings.setValue(_missionAutoLoadDirKey, missionAutoLoadDir);
}

10
src/QmlControls/QGroundControlQmlGlobal.h

@ -84,6 +84,7 @@ public:
Q_PROPERTY(bool isSaveLogPromptNotArmed READ isSaveLogPromptNotArmed WRITE setIsSaveLogPromptNotArmed NOTIFY isSaveLogPromptNotArmedChanged) Q_PROPERTY(bool isSaveLogPromptNotArmed READ isSaveLogPromptNotArmed WRITE setIsSaveLogPromptNotArmed NOTIFY isSaveLogPromptNotArmedChanged)
Q_PROPERTY(bool virtualTabletJoystick READ virtualTabletJoystick WRITE setVirtualTabletJoystick NOTIFY virtualTabletJoystickChanged) Q_PROPERTY(bool virtualTabletJoystick READ virtualTabletJoystick WRITE setVirtualTabletJoystick NOTIFY virtualTabletJoystickChanged)
Q_PROPERTY(qreal baseFontPointSize READ baseFontPointSize WRITE setBaseFontPointSize NOTIFY baseFontPointSizeChanged) Q_PROPERTY(qreal baseFontPointSize READ baseFontPointSize WRITE setBaseFontPointSize NOTIFY baseFontPointSizeChanged)
Q_PROPERTY(QString missionAutoLoadDir READ missionAutoLoadDir WRITE setMissionAutoLoadDir NOTIFY missionAutoLoadDirChanged STORED false)
//------------------------------------------------------------------------- //-------------------------------------------------------------------------
// MavLink Protocol // MavLink Protocol
@ -148,10 +149,10 @@ public:
Q_INVOKABLE QStringList loggingCategories(void) const { return QGCLoggingCategoryRegister::instance()->registeredCategories(); } Q_INVOKABLE QStringList loggingCategories(void) const { return QGCLoggingCategoryRegister::instance()->registeredCategories(); }
/// Turns on/off logging for the specified category. State is saved in app settings. /// Turns on/off logging for the specified category. State is saved in app settings.
Q_INVOKABLE void setCategoryLoggingOn(const QString& category, bool enable) { QGCLoggingCategoryRegister::instance()->setCategoryLoggingOn(category, enable); }; Q_INVOKABLE void setCategoryLoggingOn(const QString& category, bool enable) { QGCLoggingCategoryRegister::instance()->setCategoryLoggingOn(category, enable); }
/// Returns true if logging is turned on for the specified category. /// Returns true if logging is turned on for the specified category.
Q_INVOKABLE bool categoryLoggingOn(const QString& category) { return QGCLoggingCategoryRegister::instance()->categoryLoggingOn(category); }; Q_INVOKABLE bool categoryLoggingOn(const QString& category) { return QGCLoggingCategoryRegister::instance()->categoryLoggingOn(category); }
/// Updates the logging filter rules after settings have changed /// Updates the logging filter rules after settings have changed
Q_INVOKABLE void updateLoggingFilterRules(void) { QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(QString()); } Q_INVOKABLE void updateLoggingFilterRules(void) { QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(QString()); }
@ -211,6 +212,9 @@ public:
QString qgcVersion(void) const { return qgcApp()->applicationVersion(); } QString qgcVersion(void) const { return qgcApp()->applicationVersion(); }
static QString missionAutoLoadDir(void);
static void setMissionAutoLoadDir(const QString& missionAutoLoadDir);
// Overrides from QGCTool // Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox); virtual void setToolbox(QGCToolbox* toolbox);
@ -226,6 +230,7 @@ signals:
void mavlinkSystemIDChanged (int id); void mavlinkSystemIDChanged (int id);
void flightMapPositionChanged (QGeoCoordinate flightMapPosition); void flightMapPositionChanged (QGeoCoordinate flightMapPosition);
void flightMapZoomChanged (double flightMapZoom); void flightMapZoomChanged (double flightMapZoom);
void missionAutoLoadDirChanged (QString missionAutoLoadDir);
private: private:
static SettingsFact* _createSettingsFact(const QString& name); static SettingsFact* _createSettingsFact(const QString& name);
@ -261,6 +266,7 @@ private:
static const char* _virtualTabletJoystickKey; static const char* _virtualTabletJoystickKey;
static const char* _baseFontPointSizeKey; static const char* _baseFontPointSizeKey;
static const char* _missionAutoLoadDirKey;
}; };
#endif #endif

21
src/Vehicle/Vehicle.cc

@ -16,6 +16,7 @@
#include "UAS.h" #include "UAS.h"
#include "JoystickManager.h" #include "JoystickManager.h"
#include "MissionManager.h" #include "MissionManager.h"
#include "MissionController.h"
#include "GeoFenceManager.h" #include "GeoFenceManager.h"
#include "RallyPointManager.h" #include "RallyPointManager.h"
#include "CoordinateVector.h" #include "CoordinateVector.h"
@ -153,7 +154,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged); connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
_commonInit(); _commonInit();
_autopilotPlugin = _firmwarePlugin->autopilotPlugin(this); _autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
// connect this vehicle to the follow me handle manager // connect this vehicle to the follow me handle manager
connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager); connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager);
@ -294,6 +295,7 @@ void Vehicle::_commonInit(void)
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
_parameterManager = new ParameterManager(this); _parameterManager = new ParameterManager(this);
connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
// GeoFenceManager needs to access ParameterManager so make sure to create after // GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
@ -1518,7 +1520,18 @@ void Vehicle::_parametersReady(bool parametersReady)
{ {
if (parametersReady && !_missionManagerInitialRequestSent) { if (parametersReady && !_missionManagerInitialRequestSent) {
_missionManagerInitialRequestSent = true; _missionManagerInitialRequestSent = true;
_missionManager->requestMissionItems(); QString missionAutoLoadDirPath = QGroundControlQmlGlobal::missionAutoLoadDir();
if (missionAutoLoadDirPath.isEmpty()) {
_missionManager->requestMissionItems();
} else {
QmlObjectListModel* visualItems = NULL;
QmlObjectListModel* complexItems = NULL;
QDir missionAutoLoadDir(missionAutoLoadDirPath);
QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.mission").arg(_id));
if (MissionController::loadItemsFromFile(this, autoloadFilename, &visualItems, &complexItems)) {
MissionController::sendItemsToVehicle(this, visualItems);
}
}
} }
if (parametersReady) { if (parametersReady) {
@ -2032,7 +2045,7 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
void Vehicle::_newMissionItemsAvailable(void) void Vehicle::_newMissionItemsAvailable(void)
{ {
// After the initial mission request complets we ask for the geofence // After the initial mission request completes we ask for the geofence
if (!_geoFenceManagerInitialRequestSent) { if (!_geoFenceManagerInitialRequestSent) {
_geoFenceManagerInitialRequestSent = true; _geoFenceManagerInitialRequestSent = true;
_geoFenceManager->loadFromVehicle(); _geoFenceManager->loadFromVehicle();
@ -2041,7 +2054,7 @@ void Vehicle::_newMissionItemsAvailable(void)
void Vehicle::_newGeoFenceAvailable(void) void Vehicle::_newGeoFenceAvailable(void)
{ {
// After the initial mission request complets we ask for the geofence // After geofence request completes we ask for the rally points
if (!_rallyPointManagerInitialRequestSent) { if (!_rallyPointManagerInitialRequestSent) {
_rallyPointManagerInitialRequestSent = true; _rallyPointManagerInitialRequestSent = true;
_rallyPointManager->loadFromVehicle(); _rallyPointManager->loadFromVehicle();

27
src/ui/preferences/GeneralSettings.qml

@ -286,6 +286,33 @@ QGCView {
visible: QGroundControl.corePlugin.options.enableVirtualJoystick visible: QGroundControl.corePlugin.options.enableVirtualJoystick
} }
//----------------------------------------------------------------- //-----------------------------------------------------------------
//-- AutoLoad
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCCheckBox {
id: autoLoadCheckbox
anchors.verticalCenter: parent.verticalCenter
text: qsTr("AutoLoad mission directory:")
checked: QGroundControl.missionAutoLoadDir != ""
onClicked: {
autoLoadDir.enabled = checked
if (!checked) {
QGroundControl.missionAutoLoadDir = ""
autoLoadDir.text = ""
}
}
}
QGCTextField {
id: autoLoadDir
width: _editFieldWidth
enabled: autoLoadCheckbox.checked
anchors.verticalCenter: parent.verticalCenter
text: QGroundControl.missionAutoLoadDir
onEditingFinished: QGroundControl.missionAutoLoadDir = text
}
}
//-----------------------------------------------------------------
//-- Map Providers //-- Map Providers
Row { Row {
/* /*

Loading…
Cancel
Save