Commit 9e061b2d authored by Don Gagne's avatar Don Gagne

ComplexMissionItem support for Survey

parent e513494c
...@@ -99,6 +99,7 @@ ...@@ -99,6 +99,7 @@
<file alias="MapAddMissionBlack.svg">src/FlightMap/Images/MapAddMissionBlack.svg</file> <file alias="MapAddMissionBlack.svg">src/FlightMap/Images/MapAddMissionBlack.svg</file>
<file alias="MapCenter.svg">src/FlightMap/Images/MapCenter.svg</file> <file alias="MapCenter.svg">src/FlightMap/Images/MapCenter.svg</file>
<file alias="MapCenterBlack.svg">src/FlightMap/Images/MapCenterBlack.svg</file> <file alias="MapCenterBlack.svg">src/FlightMap/Images/MapCenterBlack.svg</file>
<file alias="MapDrawShape.svg">src/FlightMap/Images/MapDrawShape.svg</file>
<file alias="MapHome.svg">src/FlightMap/Images/MapHome.svg</file> <file alias="MapHome.svg">src/FlightMap/Images/MapHome.svg</file>
<file alias="MapHomeBlack.svg">src/FlightMap/Images/MapHomeBlack.svg</file> <file alias="MapHomeBlack.svg">src/FlightMap/Images/MapHomeBlack.svg</file>
<file alias="MapSync.svg">src/FlightMap/Images/MapSync.svg</file> <file alias="MapSync.svg">src/FlightMap/Images/MapSync.svg</file>
......
...@@ -261,6 +261,8 @@ HEADERS += \ ...@@ -261,6 +261,8 @@ HEADERS += \
src/MissionManager/MissionController.h \ src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \ src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \ src/MissionManager/MissionManager.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/SimpleMissionItem.h \
src/QGC.h \ src/QGC.h \
src/QGCApplication.h \ src/QGCApplication.h \
src/QGCComboBox.h \ src/QGCComboBox.h \
...@@ -388,6 +390,8 @@ SOURCES += \ ...@@ -388,6 +390,8 @@ SOURCES += \
src/MissionManager/MissionController.cc \ src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \ src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \ src/MissionManager/MissionManager.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \
src/QGC.cc \ src/QGC.cc \
src/QGCApplication.cc \ src/QGCApplication.cc \
src/QGCComboBox.cc \ src/QGCComboBox.cc \
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="-89 46 72 72" enable-background="new -89 46 72 72" xml:space="preserve">
<g transform="matrix(0.96508576,0,0,0.94661676,-1.3508671,3.6129809)">
<path fill="none" stroke="#FFFFFF" stroke-width="1.2" stroke-miterlimit="4" d="m -69.288973,77.48289 22.722433,-9.307985 2.098859,4.288973 -23.726235,9.39924 1.186311,4.471483 23.908746,-9.855514 L -41,80.768061 -66.186312,91.079848 -65,95.551331 l 25.460076,-10.403042 -2.372624,7.391635 -13.140684,5.110266"/>
</g>
<path fill="none" stroke="#FFFFFF" stroke-width="2" stroke-miterlimit="10" d="m -44.193916,62.152091 10.76806,20.623574 -9.21673,19.346005 -24.638783,-3.011404 -6.205323,-25.186312 z"/>
</svg>
...@@ -285,6 +285,8 @@ QGCView { ...@@ -285,6 +285,8 @@ QGCView {
anchors.fill: parent anchors.fill: parent
mapName: "MissionEditor" mapName: "MissionEditor"
signal mapClicked(var coordinate)
readonly property real animationDuration: 500 readonly property real animationDuration: 500
// Initial map position duplicates Fly view position // Initial map position duplicates Fly view position
...@@ -301,15 +303,15 @@ QGCView { ...@@ -301,15 +303,15 @@ QGCView {
anchors.fill: parent anchors.fill: parent
onClicked: { onClicked: {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y))
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
if (addMissionItemsButton.checked) { if (addMissionItemsButton.checked) {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y)) var index = controller.insertSimpleMissionItem(coordinate, controller.missionItems.count)
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
var index = controller.insertMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index) setCurrentItem(index)
} else { } else {
editorMap.zoomLevel = editorMap.maxZoomLevel - 2 editorMap.mapClicked(coordinate)
} }
} }
} }
...@@ -364,7 +366,7 @@ QGCView { ...@@ -364,7 +366,7 @@ QGCView {
} }
} }
// Add the mission items to the map // Add the simple mission items to the map
MapItemView { MapItemView {
model: controller.missionItems model: controller.missionItems
delegate: missionItemComponent delegate: missionItemComponent
...@@ -421,6 +423,22 @@ QGCView { ...@@ -421,6 +423,22 @@ QGCView {
} }
} }
// Add the complex mission items to the map
MapItemView {
model: controller.complexMissionItems
delegate: polygonItemComponent
}
Component {
id: polygonItemComponent
MapPolygon {
color: 'green'
path: object.polygonPath
opacity: 0.5
}
}
// Add lines between waypoints // Add lines between waypoints
MissionLineView { MissionLineView {
model: controller.waypointLines model: controller.waypointLines
...@@ -482,7 +500,7 @@ QGCView { ...@@ -482,7 +500,7 @@ QGCView {
} }
onInsert: { onInsert: {
controller.insertMissionItem(editorMap.center, i) controller.insertSimpleMissionItem(editorMap.center, i)
setCurrentItem(i) setCurrentItem(i)
} }
...@@ -522,6 +540,23 @@ QGCView { ...@@ -522,6 +540,23 @@ QGCView {
z: QGroundControl.zOrderWidgets z: QGroundControl.zOrderWidgets
} }
RoundButton {
id: addShapeButton
buttonImage: "/qmlimages/MapDrawShape.svg"
z: QGroundControl.zOrderWidgets
visible: QGroundControl.experimentalSurvey
onClicked: {
var coordinate = editorMap.center
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
var index = controller.insertComplexMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index)
checked = false
}
}
DropButton { DropButton {
id: syncButton id: syncButton
dropDirection: dropRight dropDirection: dropRight
......
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 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 "ComplexMissionItem.h"
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent)
: MissionItem(vehicle, parent)
{
}
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent)
: MissionItem(vehicle, sequenceNumber, command, frame, param1, param2, param3, param4, param5, param6, param7, autoContinue, isCurrentItem, parent)
{
}
ComplexMissionItem::ComplexMissionItem(const ComplexMissionItem& other, QObject* parent)
: MissionItem(other, parent)
{
}
const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem& other)
{
static_cast<MissionItem&>(*this) = other;
return *this;
}
QVariantList ComplexMissionItem::polygonPath(void)
{
return _polygonPath;
#if 0
QVariantList list;
list << QVariant::fromValue(QGeoCoordinate(-35.362686830000001, 149.16410282999999))
<< QVariant::fromValue(QGeoCoordinate(-35.362660579999996, 149.16606619999999))
<< QVariant::fromValue(QGeoCoordinate(-35.363832989999999, 149.16505769));
return list;
#endif
}
void ComplexMissionItem::clearPolygon(void)
{
_polygonPath.clear();
emit polygonPathChanged();
}
void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
{
_polygonPath << QVariant::fromValue(coordinate);
emit polygonPathChanged();
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 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 ComplexMissionItem_H
#define ComplexMissionItem_H
#include "MissionItem.h"
class ComplexMissionItem : public MissionItem
{
Q_OBJECT
public:
ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL);
ComplexMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent = NULL);
ComplexMissionItem(const ComplexMissionItem& other, QObject* parent = NULL);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_INVOKABLE void clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
QVariantList polygonPath(void);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return false; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
signals:
void polygonPathChanged(void);
private:
QVariantList _polygonPath;
};
#endif
...@@ -27,6 +27,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -27,6 +27,8 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h" #include "QGroundControlQmlGlobal.h"
#include <QQmlEngine>
MissionCommands::MissionCommands(QGCApplication* app) MissionCommands::MissionCommands(QGCApplication* app)
: QGCTool(app) : QGCTool(app)
, _commonMissionCommands(QStringLiteral(":/json/MavCmdInfoCommon.json")) , _commonMissionCommands(QStringLiteral(":/json/MavCmdInfoCommon.json"))
......
...@@ -27,6 +27,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -27,6 +27,8 @@ This file is part of the QGROUNDCONTROL project
#include "CoordinateVector.h" #include "CoordinateVector.h"
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "SimpleMissionItem.h"
#include "ComplexMissionItem.h"
#ifndef __mobile__ #ifndef __mobile__
#include "QGCFileDialog.h" #include "QGCFileDialog.h"
...@@ -45,6 +47,7 @@ MissionController::MissionController(QObject *parent) ...@@ -45,6 +47,7 @@ MissionController::MissionController(QObject *parent)
: QObject(parent) : QObject(parent)
, _editMode(false) , _editMode(false)
, _missionItems(NULL) , _missionItems(NULL)
, _complexMissionItems(NULL)
, _activeVehicle(NULL) , _activeVehicle(NULL)
, _autoSync(false) , _autoSync(false)
, _firstItemsFromVehicle(false) , _firstItemsFromVehicle(false)
...@@ -124,9 +127,9 @@ void MissionController::sendMissionItems(void) ...@@ -124,9 +127,9 @@ void MissionController::sendMissionItems(void)
} }
} }
int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i) int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
{ {
MissionItem * newItem = new MissionItem(_activeVehicle, this); MissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count()); newItem->setSequenceNumber(_missionItems->count());
newItem->setCoordinate(coordinate); newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT); newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
...@@ -152,6 +155,22 @@ int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i) ...@@ -152,6 +155,22 @@ int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
return _missionItems->count() - 1; return _missionItems->count() - 1;
} }
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
ComplexMissionItem * newItem = new ComplexMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count());
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initMissionItem(newItem);
_missionItems->insert(i, newItem);
_complexMissionItems->append(newItem);
_recalcAll();
return _missionItems->count() - 1;
}
void MissionController::removeMissionItem(int index) void MissionController::removeMissionItem(int index)
{ {
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index)); MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index));
...@@ -218,7 +237,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL ...@@ -218,7 +237,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
return false; return false;
} }
MissionItem* item = new MissionItem(_activeVehicle, this); MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(itemValue.toObject(), errorString)) { if (item->load(itemValue.toObject(), errorString)) {
missionItems->append(item); missionItems->append(item);
} else { } else {
...@@ -228,7 +247,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL ...@@ -228,7 +247,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
} }
if (json.contains(_jsonPlannedHomePositionKey)) { if (json.contains(_jsonPlannedHomePositionKey)) {
MissionItem* item = new MissionItem(_activeVehicle, this); MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) { if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
missionItems->insert(0, item); missionItems->insert(0, item);
...@@ -263,7 +282,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM ...@@ -263,7 +282,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
if (versionOk) { if (versionOk) {
while (!stream.atEnd()) { while (!stream.atEnd()) {
MissionItem* item = new MissionItem(_activeVehicle, this); MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(stream)) { if (item->load(stream)) {
missionItems->append(item); missionItems->append(item);
...@@ -612,13 +631,24 @@ void MissionController::_initAllMissionItems(void) ...@@ -612,13 +631,24 @@ void MissionController::_initAllMissionItems(void)
qDebug() << "home item" << homeItem->coordinate(); qDebug() << "home item" << homeItem->coordinate();
QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
for (int i=0; i<_missionItems->count(); i++) { for (int i=0; i<_missionItems->count(); i++) {
_initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i))); MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
if (!item->simpleItem()) {
newComplexItems->append(item);
}
_initMissionItem(item);
} }
delete _complexMissionItems;
_complexMissionItems = newComplexItems;
_recalcAll(); _recalcAll();
emit missionItemsChanged(); emit missionItemsChanged();
emit complexMissionItemsChanged();
_missionItems->setDirty(false); _missionItems->setDirty(false);
...@@ -773,6 +803,11 @@ QmlObjectListModel* MissionController::missionItems(void) ...@@ -773,6 +803,11 @@ QmlObjectListModel* MissionController::missionItems(void)
return _missionItems; return _missionItems;
} }
QmlObjectListModel* MissionController::complexMissionItems(void)
{
return _complexMissionItems;
}
bool MissionController::_findLastAltitude(double* lastAltitude) bool MissionController::_findLastAltitude(double* lastAltitude)
{ {
bool found = false; bool found = false;
...@@ -831,7 +866,7 @@ double MissionController::_normalizeLon(double lon) ...@@ -831,7 +866,7 @@ 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* missionItems, bool addToCenter) void MissionController::_addPlannedHomePosition(QmlObjectListModel* missionItems, bool addToCenter)
{ {
MissionItem* homeItem = new MissionItem(_activeVehicle, this); MissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
missionItems->insert(0, homeItem); missionItems->insert(0, homeItem);
if (missionItems->count() > 1 && addToCenter) { if (missionItems->count() > 1 && addToCenter) {
......
...@@ -29,6 +29,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -29,6 +29,8 @@ This file is part of the QGROUNDCONTROL project
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "MissionItem.h"
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog) Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
...@@ -41,6 +43,7 @@ public: ...@@ -41,6 +43,7 @@ public:
~MissionController(); ~MissionController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged) Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexMissionItems READ complexMissionItems NOTIFY complexMissionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged) Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged)
...@@ -57,11 +60,15 @@ public: ...@@ -57,11 +60,15 @@ public:
Q_INVOKABLE QStringList getMobileMissionFiles(void); Q_INVOKABLE QStringList getMobileMissionFiles(void);
/// @param i: index to insert at /// @param i: index to insert at
Q_INVOKABLE int insertMissionItem(QGeoCoordinate coordinate, int i); Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int i);
/// @param i: index to insert at
Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i);
// Property accessors // Property accessors
QmlObjectListModel* missionItems(void); QmlObjectListModel* missionItems(void);
QmlObjectListModel* complexMissionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; } QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool autoSync(void) { return _autoSync; } bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync); void setAutoSync(bool autoSync);
...@@ -69,6 +76,7 @@ public: ...@@ -69,6 +76,7 @@ public:
signals: signals:
void missionItemsChanged(void); void missionItemsChanged(void);
void complexMissionItemsChanged(void);
void waypointLinesChanged(void); void waypointLinesChanged(void);
void autoSyncChanged(bool autoSync); void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void); void newItemsFromVehicle(void);
...@@ -111,6 +119,7 @@ private: ...@@ -111,6 +119,7 @@ private:
private: private:
bool _editMode; bool _editMode;
QmlObjectListModel* _missionItems; QmlObjectListModel* _missionItems;
QmlObjectListModel* _complexMissionItems;
QmlObjectListModel _waypointLines; QmlObjectListModel _waypointLines;
Vehicle* _activeVehicle; Vehicle* _activeVehicle;
bool _autoSync; bool _autoSync;
......
...@@ -137,7 +137,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType) ...@@ -137,7 +137,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QGeoCoordinate coordinate(37.803784, -122.462276); QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->insertMissionItem(coordinate, _missionController->missionItems()->count()); _missionController->insertSimpleMissionItem(coordinate, _missionController->missionItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true); QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
...@@ -182,7 +182,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp ...@@ -182,7 +182,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
_missionController = new MissionController(); _missionController = new MissionController();
Q_CHECK_PTR(_missionController); Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */); _missionController->start(true /* editMode */);
_missionController->insertMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count()); _missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
// Go online to empty vehicle // Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType); MissionControllerManagerTest::_initForFirmwareType(firmwareType);
......
...@@ -28,8 +28,6 @@ This file is part of the QGROUNDCONTROL project ...@@ -28,8 +28,6 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h" #include "QGCApplication.h"
#include "JsonHelper.h" #include "JsonHelper.h"
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
const double MissionItem::defaultAltitude = 25.0; const double MissionItem::defaultAltitude = 25.0;
FactMetaData* MissionItem::_altitudeMetaData = NULL; FactMetaData* MissionItem::_altitudeMetaData = NULL;
...@@ -71,22 +69,6 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { ...@@ -71,22 +69,6 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
}; };
QDebug operator<<(QDebug dbg, const MissionItem& missionItem)
{
QDebugStateSaver saver(dbg);
dbg.nospace() << "MissionItem(" << missionItem.coordinate() << ")";
return dbg;
}
QDebug operator<<(QDebug dbg, const MissionItem* missionItem)
{
QDebugStateSaver saver(dbg);
dbg.nospace() << "MissionItem(" << missionItem->coordinate() << ")";
return dbg;
}
MissionItem::MissionItem(Vehicle* vehicle, QObject* parent) MissionItem::MissionItem(Vehicle* vehicle, QObject* parent)
: QObject(parent) : QObject(parent)
, _vehicle(vehicle) , _vehicle(vehicle)
......
...@@ -40,8 +40,7 @@ ...@@ -40,8 +40,7 @@
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "MissionCommands.h" #include "MissionCommands.h"
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog) // Abstract base class for Simple and Complex MissionItem obejcts.
class MissionItem : public QObject class MissionItem : public QObject
{ {
Q_OBJECT Q_OBJECT
...@@ -77,7 +76,6 @@ public: ...@@ -77,7 +76,6 @@ public:
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged) Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandChanged) Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandChanged) Q_PROPERTY(QString commandName READ commandName NOTIFY commandChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint
Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged) Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged)
...@@ -90,6 +88,16 @@ public: ...@@ -90,6 +88,16 @@ public:
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY commandChanged) Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY commandChanged)
Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged) Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
// Mission item has two coordinates associated with them:
// coordinate: This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
// exitCoordinate This is the exit point for a waypoint line coming out of the item. For a SimpleMissionItem this will be the same as
// coordinate. For a ComplexMissionItem it may be different than the entry coordinate.
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged)
/// @return true: SimpleMissionItem, false: ComplexMissionItem
Q_PROPERTY(bool simpleItem READ simpleItem NOTIFY simpleItemChanged)
// These properties are used to display the editing ui // These properties are used to display the editing ui
Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY uiModelChanged) Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY uiModelChanged)
Q_PROPERTY(QmlObjectListModel* comboboxFacts READ comboboxFacts NOTIFY uiModelChanged) Q_PROPERTY(QmlObjectListModel* comboboxFacts READ comboboxFacts NOTIFY uiModelChanged)
...@@ -179,6 +187,10 @@ public: ...@@ -179,6 +187,10 @@ public:
static const double defaultAltitude; static const double defaultAltitude;
// Pure virtuals which must be provides by derived classes
virtual bool simpleItem(void) const = 0;
virtual QGeoCoordinate exitCoordinate(void) const = 0;
public slots: public slots:
void setDefaultsForCommand(void); void setDefaultsForCommand(void);
...@@ -188,6 +200,7 @@ signals: ...@@ -188,6 +200,7 @@ signals:
void azimuthChanged (double azimuth); void azimuthChanged (double azimuth);
void commandChanged (MavlinkQmlSingleton::Qml_MAV_CMD command); void commandChanged (MavlinkQmlSingleton::Qml_MAV_CMD command);
void coordinateChanged (const QGeoCoordinate& coordinate); void coordinateChanged (const QGeoCoordinate& coordinate);
void exitCoordinateChanged (const QGeoCoordinate& exitCoordinate);
void dirtyChanged (bool dirty); void dirtyChanged (bool dirty);
void distanceChanged (double distance); void distanceChanged (double distance);
void frameChanged (int frame); void frameChanged (int frame);
...@@ -198,6 +211,7 @@ signals: ...@@ -198,6 +211,7 @@ signals:
void sequenceNumberChanged (int sequenceNumber); void sequenceNumberChanged (int sequenceNumber);
void uiModelChanged (void); void uiModelChanged (void);
void showHomePositionChanged (bool showHomePosition); void showHomePositionChanged (bool showHomePosition);
void simpleItemChanged (bool simpleItem);
private slots: private slots:
void _setDirtyFromSignal(void); void _setDirtyFromSignal(void);
...@@ -276,7 +290,4 @@ private: ...@@ -276,7 +290,4 @@ private:
static const char* _jsonCoordinateKey; static const char* _jsonCoordinateKey;
}; };
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
QDebug operator<<(QDebug dbg, const MissionItem* missionItem);
#endif #endif
...@@ -22,7 +22,7 @@ ...@@ -22,7 +22,7 @@
======================================================================*/ ======================================================================*/
#include "MissionItemTest.h" #include "MissionItemTest.h"
#include "MissionItem.h" #include "SimpleMissionItem.h"
const MissionItemTest::ItemInfo_t MissionItemTest::_rgItemInfo[] = { const MissionItemTest::ItemInfo_t MissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
...@@ -184,7 +184,7 @@ void MissionItemTest::_test(void) ...@@ -184,7 +184,7 @@ void MissionItemTest::_test(void)
void MissionItemTest::_testDefaultValues(void) void MissionItemTest::_testDefaultValues(void)
{ {
MissionItem item(NULL /* Vehicle */); SimpleMissionItem item(NULL /* Vehicle */);
item.setCommand(MAV_CMD_NAV_WAYPOINT); item.setCommand(MAV_CMD_NAV_WAYPOINT);
item.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); item.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
......
...@@ -29,6 +29,7 @@ ...@@ -29,6 +29,7 @@
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "SimpleMissionItem.h"
QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog") QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
...@@ -64,7 +65,7 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) ...@@ -64,7 +65,7 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
int firstIndex = skipFirstItem ? 1 : 0; int firstIndex = skipFirstItem ? 1 : 0;
for (int i=firstIndex; i<missionItems.count(); i++) { for (int i=firstIndex; i<missionItems.count(); i++) {
_missionItems.append(new MissionItem(*qobject_cast<const MissionItem*>(missionItems[i]))); _missionItems.append(new SimpleMissionItem(*qobject_cast<const SimpleMissionItem*>(missionItems[i])));
MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1)); MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1));
...@@ -252,7 +253,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message) ...@@ -252,7 +253,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
_requestItemRetryCount = 0; _requestItemRetryCount = 0;
_itemIndicesToRead.removeOne(missionItem.seq); _itemIndicesToRead.removeOne(missionItem.seq);
MissionItem* item = new MissionItem(_vehicle, MissionItem* item = new SimpleMissionItem(_vehicle,
missionItem.seq, missionItem.seq,
(MAV_CMD)missionItem.command, (MAV_CMD)missionItem.command,
(MAV_FRAME)missionItem.frame, (MAV_FRAME)missionItem.frame,
...@@ -432,7 +433,7 @@ QmlObjectListModel* MissionManager::copyMissionItems(void) ...@@ -432,7 +433,7 @@ QmlObjectListModel* MissionManager::copyMissionItems(void)
QmlObjectListModel* list = new QmlObjectListModel(); QmlObjectListModel* list = new QmlObjectListModel();
for (int i=0; i<_missionItems.count(); i++) { for (int i=0; i<_missionItems.count(); i++) {
list->append(new MissionItem(*qobject_cast<const MissionItem*>(_missionItems[i]))); list->append(new SimpleMissionItem(*qobject_cast<const SimpleMissionItem*>(_missionItems[i])));
} }
return list; return list;
......
...@@ -24,6 +24,7 @@ ...@@ -24,6 +24,7 @@
#include "MissionManagerTest.h" #include "MissionManagerTest.h"
#include "LinkManager.h" #include "LinkManager.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
const MissionManagerTest::TestCase_t MissionManagerTest::_rgTestCases[] = { const MissionManagerTest::TestCase_t MissionManagerTest::_rgTestCases[] = {
{ "0\t0\t3\t16\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 0, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_WAYPOINT, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } }, { "0\t0\t3\t16\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 0, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_WAYPOINT, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
...@@ -48,7 +49,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f ...@@ -48,7 +49,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QmlObjectListModel* list = new QmlObjectListModel(); QmlObjectListModel* list = new QmlObjectListModel();
// Editor has a home position item on the front, so we do the same // Editor has a home position item on the front, so we do the same
MissionItem* homeItem = new MissionItem(NULL /* Vehicle */, this); SimpleMissionItem* homeItem = new SimpleMissionItem(NULL /* Vehicle */, this);
homeItem->setHomePositionSpecialCase(true); homeItem->setHomePositionSpecialCase(true);
homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT); homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
homeItem->setCoordinate(QGeoCoordinate(47.3769, 8.549444, 0)); homeItem->setCoordinate(QGeoCoordinate(47.3769, 8.549444, 0));
...@@ -58,7 +59,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f ...@@ -58,7 +59,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
for (size_t i=0; i<_cTestCases; i++) { for (size_t i=0; i<_cTestCases; i++) {
const TestCase_t* testCase = &_rgTestCases[i]; const TestCase_t* testCase = &_rgTestCases[i];
MissionItem* item = new MissionItem(NULL /* Vehicle */, list); SimpleMissionItem* item = new SimpleMissionItem(NULL /* Vehicle */, list);
QTextStream loadStream(testCase->itemStream, QIODevice::ReadOnly); QTextStream loadStream(testCase->itemStream, QIODevice::ReadOnly);
QVERIFY(item->load(loadStream)); QVERIFY(item->load(loadStream));
......
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 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 "SimpleMissionItem.h"
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
: MissionItem(vehicle, parent)
{
}
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent)
: MissionItem(vehicle, sequenceNumber, command, frame, param1, param2, param3, param4, param5, param6, param7, autoContinue, isCurrentItem, parent)
{
}
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent)
: MissionItem(other, parent)
{
}
const SimpleMissionItem& SimpleMissionItem::operator=(const SimpleMissionItem& other)
{
static_cast<MissionItem&>(*this) = other;
return *this;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 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 SimpleMissionItem_H
#define SimpleMissionItem_H
#include "MissionItem.h"
class SimpleMissionItem : public MissionItem
{
Q_OBJECT
public:
SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL);
SimpleMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent = NULL);
SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL);
const SimpleMissionItem& operator=(const SimpleMissionItem& other);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return true; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
private:
};
#endif
...@@ -30,7 +30,7 @@ ...@@ -30,7 +30,7 @@
QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog") QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog") QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog") QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
QGCLoggingCategoryRegister* _instance = NULL; QGCLoggingCategoryRegister* _instance = NULL;
......
...@@ -34,6 +34,7 @@ ...@@ -34,6 +34,7 @@
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog) Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog) Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog) Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
/// @def QGC_LOGGING_CATEGORY /// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a /// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
This diff is collapsed.
...@@ -206,3 +206,18 @@ void QGroundControlQmlGlobal::setVirtualTabletJoystick(bool enabled) ...@@ -206,3 +206,18 @@ void QGroundControlQmlGlobal::setVirtualTabletJoystick(bool enabled)
emit virtualTabletJoystickChanged(enabled); emit virtualTabletJoystickChanged(enabled);
} }
} }
bool QGroundControlQmlGlobal::experimentalSurvey(void) const
{
QSettings settings;
return settings.value("ExperimentalSurvey", false).toBool();
}
void QGroundControlQmlGlobal::setExperimentalSurvey(bool experimentalSurvey)
{
QSettings settings;
settings.setValue("ExperimentalSurvey", experimentalSurvey);
emit experimentalSurveyChanged(experimentalSurvey);
}
...@@ -79,6 +79,9 @@ public: ...@@ -79,6 +79,9 @@ public:
Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT) Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT)
Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged) Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged)
/// @ return: true: experimental survey ip code is turned on
Q_PROPERTY(bool experimentalSurvey READ experimentalSurvey WRITE setExperimentalSurvey NOTIFY experimentalSurveyChanged)
Q_INVOKABLE void saveGlobalSetting (const QString& key, const QString& value); Q_INVOKABLE void saveGlobalSetting (const QString& key, const QString& value);
Q_INVOKABLE QString loadGlobalSetting (const QString& key, const QString& defaultValue); Q_INVOKABLE QString loadGlobalSetting (const QString& key, const QString& defaultValue);
Q_INVOKABLE void saveBoolGlobalSetting (const QString& key, bool value); Q_INVOKABLE void saveBoolGlobalSetting (const QString& key, bool value);
...@@ -133,6 +136,9 @@ public: ...@@ -133,6 +136,9 @@ public:
void setIsVersionCheckEnabled (bool enable); void setIsVersionCheckEnabled (bool enable);
void setMavlinkSystemID (int id); void setMavlinkSystemID (int id);
bool experimentalSurvey(void) const;
void setExperimentalSurvey(bool experimentalSurvey);
// Overrides from QGCTool // Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox); virtual void setToolbox(QGCToolbox* toolbox);
...@@ -146,6 +152,7 @@ signals: ...@@ -146,6 +152,7 @@ signals:
void isVersionCheckEnabledChanged (bool enabled); void isVersionCheckEnabledChanged (bool enabled);
void mavlinkSystemIDChanged (int id); void mavlinkSystemIDChanged (int id);
void flightMapPositionChanged (QGeoCoordinate flightMapPosition); void flightMapPositionChanged (QGeoCoordinate flightMapPosition);
void experimentalSurveyChanged (bool experimentalSurvey);
private: private:
FlightMapSettings* _flightMapSettings; FlightMapSettings* _flightMapSettings;
......
...@@ -32,6 +32,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -32,6 +32,8 @@ This file is part of the QGROUNDCONTROL project
#include <QApplication> #include <QApplication>
#include <QSslSocket> #include <QSslSocket>
#include <QProcessEnvironment> #include <QProcessEnvironment>
#include <QHostAddress>
#include <QUdpSocket>
#include "QGCApplication.h" #include "QGCApplication.h"
......
...@@ -242,6 +242,8 @@ Rectangle { ...@@ -242,6 +242,8 @@ Rectangle {
width: parent.width width: parent.width
} }
//-----------------------------------------------------------------
//-- Offline mission editing settings
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
...@@ -257,6 +259,19 @@ Rectangle { ...@@ -257,6 +259,19 @@ Rectangle {
indexModel: false indexModel: false
} }
} }
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: parent.width
}
//-----------------------------------------------------------------
//-- Experimental Survey settings
QGCCheckBox {
text: "Experimental Survey [WIP - no bugs reports please]"
checked: QGroundControl.experimentalSurvey
onClicked: QGroundControl.experimentalSurvey = checked
}
} }
} }
} }
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