Commit 32b8a549 authored by Don Gagne's avatar Don Gagne

Simple/Complex item rearchitecture

Plus new unit tests
parent e27ab01d
......@@ -263,6 +263,7 @@ HEADERS += \
src/MissionManager/MissionManager.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/QGC.h \
src/QGCApplication.h \
src/QGCComboBox.h \
......@@ -392,6 +393,7 @@ SOURCES += \
src/MissionManager/MissionManager.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/QGC.cc \
src/QGCApplication.cc \
src/QGCComboBox.cc \
......@@ -508,6 +510,7 @@ HEADERS += \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionItemTest.h \
src/MissionManager/MissionManagerTest.h \
src/MissionManager/SimpleMissionItemTest.h \
src/qgcunittest/GeoTest.h \
src/qgcunittest/FileDialogTest.h \
src/qgcunittest/FileManagerTest.h \
......@@ -531,6 +534,7 @@ SOURCES += \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionItemTest.cc \
src/MissionManager/MissionManagerTest.cc \
src/MissionManager/SimpleMissionItemTest.cc \
src/qgcunittest/GeoTest.cc \
src/qgcunittest/FileDialogTest.cc \
src/qgcunittest/FileManagerTest.cc \
......
......@@ -89,7 +89,7 @@ FlightMap {
// Add the mission items to the map
MissionItemView {
model: _mainIsMap ? _missionController.missionItems : 0
model: _mainIsMap ? _missionController.visualItems : 0
}
// Add lines between waypoints
......
......@@ -42,8 +42,11 @@ MapQuickItem {
sourceItem:
MissionItemIndexLabel {
id: _label
isCurrentItem: missionItem.isCurrentItem
label: missionItem.sequenceNumber == 0 ? "H" : missionItem.sequenceNumber
isCurrentItem: _isCurrentItem
label: _sequenceNumber == 0 ? "H" : missionItem.sequenceNumber
onClicked: _item.clicked()
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
property bool _sequenceNumber: missionItem ? missionItem.sequenceNumber : 0
}
}
......@@ -40,7 +40,7 @@ import QGroundControl.Controllers 1.0
QGCView {
id: _root
property bool syncNeeded: controller.missionItems.dirty // Unsaved changes, visible to parent container
property bool syncNeeded: controller.visualItems.dirty // Unsaved changes, visible to parent container
viewPanel: panel
topDialogMargin: height - mainWindow.availableHeight
......@@ -60,13 +60,11 @@ QGCView {
readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
property var _missionItems: controller.missionItems
property var _visualItems: controller.visualItems
property var _currentMissionItem
property bool _firstVehiclePosition: true
property var activeVehiclePosition: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property bool _syncInProgress: _activeVehicle ? _activeVehicle.missionManager.inProgress : false
onActiveVehiclePositionChanged: updateMapToVehiclePosition()
Connections {
......@@ -119,19 +117,19 @@ QGCView {
/// Fix the map viewport to the current mission items.
function fitViewportToMissionItems() {
if (_missionItems.count == 1) {
editorMap.center = _missionItems.get(0).coordinate
if (_visualItems.count == 1) {
editorMap.center = _visualItems.get(0).coordinate
} else {
var missionItem = _missionItems.get(0)
var missionItem = _visualItems.get(0)
var north = normalizeLat(missionItem.coordinate.latitude)
var south = north
var east = normalizeLon(missionItem.coordinate.longitude)
var west = east
for (var i=1; i<_missionItems.count; i++) {
missionItem = _missionItems.get(i)
for (var i=1; i<_visualItems.count; i++) {
missionItem = _visualItems.get(i)
if (missionItem.specifiesCoordinate && !missionItem.standaloneCoordinate) {
if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) {
var lat = normalizeLat(missionItem.coordinate.latitude)
var lon = normalizeLon(missionItem.coordinate.longitude)
......@@ -161,7 +159,7 @@ QGCView {
onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync)
*/
onMissionItemsChanged: itemDragger.clearItem()
onVisualItemsChanged: itemDragger.clearItem()
onNewItemsFromVehicle: fitViewportToMissionItems()
}
......@@ -177,12 +175,12 @@ QGCView {
function setCurrentItem(index) {
_currentMissionItem = undefined
for (var i=0; i<_missionItems.count; i++) {
for (var i=0; i<_visualItems.count; i++) {
if (i == index) {
_currentMissionItem = _missionItems.get(i)
_currentMissionItem = _visualItems.get(i)
_currentMissionItem.isCurrentItem = true
} else {
_missionItems.get(i).isCurrentItem = false
_visualItems.get(i).isCurrentItem = false
}
}
}
......@@ -266,7 +264,7 @@ QGCView {
QGCComboBox {
id: toCombo
model: _missionItems.count
model: _visualItems.count
currentIndex: _moveDialogMissionItemIndex
}
}
......@@ -308,7 +306,7 @@ QGCView {
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
if (addMissionItemsButton.checked) {
var index = controller.insertSimpleMissionItem(coordinate, controller.missionItems.count)
var index = controller.insertSimpleMissionItem(coordinate, controller.visualItems.count)
setCurrentItem(index)
} else {
editorMap.mapClicked(coordinate)
......@@ -368,7 +366,7 @@ QGCView {
// Add the simple mission items to the map
MapItemView {
model: controller.missionItems
model: controller.visualItems
delegate: missionItemComponent
}
......@@ -400,7 +398,7 @@ QGCView {
target: object
onIsCurrentItemChanged: updateItemIndicator()
onCommandChanged: updateItemIndicator()
onSpecifiesCoordinateChanged: updateItemIndicator()
}
// These are the non-coordinate child mission items attached to this item
......@@ -425,7 +423,7 @@ QGCView {
// Add the complex mission items to the map
MapItemView {
model: controller.complexMissionItems
model: controller.complexVisualItems
delegate: polygonItemComponent
}
......@@ -480,10 +478,10 @@ QGCView {
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
height: Math.min(contentHeight, parent.height)
height: parent.height
spacing: _margin / 2
orientation: ListView.Vertical
model: controller.missionItems
model: controller.visualItems
cacheBuffer: height * 2
delegate: MissionItemEditor {
......@@ -504,7 +502,7 @@ QGCView {
setCurrentItem(i)
}
onMoveHomeToMapCenter: controller.missionItems.get(0).coordinate = editorMap.center
onMoveHomeToMapCenter: controller.visualItems.get(0).coordinate = editorMap.center
}
} // ListView
} // Item - Mission Item editor
......@@ -551,7 +549,7 @@ QGCView {
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)
var index = controller.insertComplexMissionItem(coordinate, controller.visualItems.count)
setCurrentItem(index)
checked = false
}
......@@ -565,8 +563,8 @@ QGCView {
exclusiveGroup: _dropButtonsExclusiveGroup
z: QGroundControl.zOrderWidgets
dropDownComponent: syncDropDownComponent
enabled: !_syncInProgress
rotateImage: _syncInProgress
enabled: !controller.syncInProgress
rotateImage: controller.syncInProgress
}
DropButton {
......@@ -589,7 +587,7 @@ QGCView {
onClicked: {
centerMapButton.hideDropDown()
editorMap.center = controller.missionItems.get(0).coordinate
editorMap.center = controller.visualItems.get(0).coordinate
}
}
......@@ -688,7 +686,7 @@ QGCView {
anchors.bottom: parent.bottom
z: QGroundControl.zOrderTopMost
currentMissionItem: _currentMissionItem
missionItems: controller.missionItems
missionItems: controller.visualItems
expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2)
}
} // FlightMap
......@@ -758,7 +756,7 @@ QGCView {
QGCButton {
text: "Send to vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......@@ -768,7 +766,7 @@ QGCView {
QGCButton {
text: "Load from vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......@@ -786,6 +784,7 @@ QGCView {
QGCButton {
text: "Save to file..."
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......@@ -795,6 +794,7 @@ QGCView {
QGCButton {
text: "Load from file..."
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......
......@@ -114,7 +114,7 @@ Rectangle {
Item {
height: graphRow.height
width: ScreenTools.smallFontPixelWidth * 2
visible: object.specifiesCoordinate && !object.standaloneCoordinate
visible: object.specifiesCoordinate && !object.isStandaloneCoordinate
property real availableHeight: height - ScreenTools.smallFontPixelHeight - indicator.height
......
......@@ -23,43 +23,19 @@ This file is part of the QGROUNDCONTROL project
#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)
: VisualMissionItem(vehicle, parent)
, _dirty(false)
{
}
ComplexMissionItem::ComplexMissionItem(const ComplexMissionItem& other, QObject* parent)
: MissionItem(other, parent)
: VisualMissionItem(other, parent)
, _dirty(false)
{
}
const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem& other)
{
static_cast<MissionItem&>(*this) = other;
return *this;
}
QVariantList ComplexMissionItem::polygonPath(void)
{
return _polygonPath;
......@@ -85,3 +61,33 @@ void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
_polygonPath << QVariant::fromValue(coordinate);
emit polygonPathChanged();
}
int ComplexMissionItem::nextSequenceNumber(void) const
{
return _sequenceNumber + _missionItems.count();
}
void ComplexMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
if (_coordinate != coordinate) {
_coordinate = coordinate;
emit coordinateChanged(_coordinate);
}
}
void ComplexMissionItem::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(_dirty);
}
}
bool ComplexMissionItem::save(QJsonObject& missionObject, QJsonArray& missionItems, QString& errorString)
{
Q_UNUSED(missionObject);
Q_UNUSED(missionItems);
errorString = "Complex save NYI";
return false;
}
......@@ -24,34 +24,17 @@
#ifndef ComplexMissionItem_H
#define ComplexMissionItem_H
#include "VisualMissionItem.h"
#include "MissionItem.h"
class ComplexMissionItem : public MissionItem
class ComplexMissionItem : public VisualMissionItem
{
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);
......@@ -59,15 +42,38 @@ public:
QVariantList polygonPath(void);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return false; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
const QList<MissionItem*>& missionItems(void) { return _missionItems; }
/// @return The next sequence number to use after this item. Takes into account child items of the complex item
int nextSequenceNumber(void) const;
// Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final { return true; }
QString commandDescription (void) const final { return "Survey"; }
QString commandName (void) const final { return "Survey"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _coordinate; }
bool coordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate);
bool save (QJsonObject& missionObject, QJsonArray& missionItems, QString& errorString) final;
signals:
void polygonPathChanged(void);
private:
bool _dirty;
QVariantList _polygonPath;
QList<MissionItem*> _missionItems;
QGeoCoordinate _coordinate;
};
#endif
......@@ -95,7 +95,7 @@ public:
Q_PROPERTY(bool friendlyEdit READ friendlyEdit CONSTANT)
Q_PROPERTY(QString friendlyName READ friendlyName CONSTANT)
Q_PROPERTY(QString rawName READ rawName CONSTANT)
Q_PROPERTY(bool standaloneCoordinate READ standaloneCoordinate CONSTANT)
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
MavlinkQmlSingleton::Qml_MAV_CMD qmlCommand(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; }
......@@ -106,7 +106,7 @@ public:
bool friendlyEdit (void) const { return _friendlyEdit; }
QString friendlyName (void) const { return _friendlyName; }
QString rawName (void) const { return _rawName; }
bool standaloneCoordinate(void) const { return _standaloneCoordinate; }
bool isStandaloneCoordinate(void) const { return _standaloneCoordinate; }
bool specifiesCoordinate (void) const { return _specifiesCoordinate; }
const QMap<int, MavCmdParamInfo*>& paramInfoMap(void) const { return _paramInfoMap; }
......
This diff is collapsed.
......@@ -30,7 +30,7 @@ This file is part of the QGROUNDCONTROL project
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "MissionItem.h"
#include "VisualMissionItem.h"
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
......@@ -42,8 +42,8 @@ public:
MissionController(QObject* parent = NULL);
~MissionController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexMissionItems READ complexMissionItems NOTIFY complexMissionItemsChanged)
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(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged)
......@@ -67,16 +67,17 @@ public:
// Property accessors
QmlObjectListModel* missionItems(void);
QmlObjectListModel* complexMissionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* complexVisualItems (void) { return _complexItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync);
bool syncInProgress(void);
signals:
void missionItemsChanged(void);
void complexMissionItemsChanged(void);
void visualItemsChanged(void);
void complexVisualItemsChanged(void);
void waypointLinesChanged(void);
void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void);
......@@ -85,41 +86,40 @@ signals:
private slots:
void _newMissionItemsAvailableFromVehicle();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemFrameChanged(int frame);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _itemCommandChanged(void);
void _activeVehicleChanged(Vehicle* activeVehicle);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
void _dirtyChanged(bool dirty);
void _inProgressChanged(bool inProgress);
void _currentMissionItemChanged(int sequenceNumber);
void _recalcWaypointLines(void);
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 _initAllVisualItems(void);
void _deinitAllVisualItems(void);
void _initVisualItem(VisualMissionItem* item);
void _deinitVisualItem(VisualMissionItem* item);
void _autoSyncSend(void);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
void _calcPrevWaypointValues(double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
bool _findLastAltitude(double* lastAltitude);
bool _findLastAcceptanceRadius(double* lastAcceptanceRadius);
void _addPlannedHomePosition(QmlObjectListModel* missionItems, bool addToCenter);
void _addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter);
double _normalizeLat(double lat);
double _normalizeLon(double lon);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* missionItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* missionItems, QString& errorString);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
void _loadMissionFromFile(const QString& file);
void _saveMissionToFile(const QString& file);
private:
bool _editMode;
QmlObjectListModel* _missionItems;
QmlObjectListModel* _complexMissionItems;
QmlObjectListModel* _visualItems;
QmlObjectListModel* _complexItems;
QmlObjectListModel _waypointLines;
Vehicle* _activeVehicle;
bool _autoSync;
......
......@@ -63,7 +63,7 @@ void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareTy
}
QVERIFY(!_missionManager->inProgress());
QCOMPARE(_missionManager->missionItems()->count(), 0);
QCOMPARE(_missionManager->missionItems().count(), 0);
_multiSpyMissionManager->clearAllSignals();
}
......
......@@ -24,6 +24,7 @@
#include "MissionControllerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
MissionControllerTest::MissionControllerTest(void)
: _multiSpyMissionController(NULL)
......@@ -62,7 +63,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
_rgMissionItemSignals[coordinateChangedSignalIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
// MissionController signals
_rgMissionControllerSignals[missionItemsChangedSignalIndex] = SIGNAL(missionItemsChanged());
_rgMissionControllerSignals[visualItemsChangedSignalIndex] = SIGNAL(visualItemsChanged());
_rgMissionControllerSignals[waypointLinesChangedSignalIndex] = SIGNAL(waypointLinesChanged());
if (!_missionController) {
......@@ -80,17 +81,17 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
}
// All signals should some through on start
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
_multiSpyMissionController->clearAllSignals();
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
// Empty vehicle only has home position
QCOMPARE(missionItems->count(), 1);
QCOMPARE(visualItems->count(), 1);
// Home position should be in first slot, but not yet valid
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(visualItems->get(0));
QVERIFY(homeItem);
QCOMPARE(homeItem->homePosition(), true);
......@@ -113,9 +114,9 @@ void MissionControllerTest::_testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType)
// FYI: A significant amount of empty vehicle testing is in _initForFirmwareType since that
// sets up an empty vehicle
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(visualItems->get(0));
QVERIFY(homeItem);
_setupMissionItemSignals(homeItem);
......@@ -137,17 +138,17 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->insertSimpleMissionItem(coordinate, _missionController->missionItems()->count());
_missionController->insertSimpleMissionItem(coordinate, _missionController->visualItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
QCOMPARE(missionItems->count(), 2);
QCOMPARE(visualItems->count(), 2);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(1));
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(visualItems->get(0));
SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(1));
QVERIFY(homeItem);
QVERIFY(item);
......@@ -182,13 +183,13 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count());
// Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
// Make sure our offline mission items are still there
QCOMPARE(_missionController->missionItems()->count(), 2);
QCOMPARE(_missionController->visualItems()->count(), 2);
}
void MissionControllerTest::_testOfflineToOnlineAPM(void)
......@@ -201,7 +202,7 @@ void MissionControllerTest::_testOfflineToOnlinePX4(void)
_testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
}
void MissionControllerTest::_setupMissionItemSignals(MissionItem* item)
void MissionControllerTest::_setupMissionItemSignals(SimpleMissionItem* item)
{
delete _multiSpyMissionItem;
......
......@@ -30,6 +30,7 @@
#include "MultiSignalSpy.h"
#include "MissionControllerManagerTest.h"
#include "MissionController.h"
#include "SimpleMissionItem.h"
#include <QGeoCoordinate>
......@@ -55,7 +56,7 @@ private:
void _testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType);
void _testAddWaypointWorker(MAV_AUTOPILOT firmwareType);
void _testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType);
void _setupMissionItemSignals(MissionItem* item);
void _setupMissionItemSignals(SimpleMissionItem* item);
// MissiomItems signals
......@@ -72,13 +73,13 @@ private:
// MissionController signals
enum {
missionItemsChangedSignalIndex = 0,
visualItemsChangedSignalIndex = 0,
waypointLinesChangedSignalIndex,
missionControllerMaxSignalIndex
};
enum {
missionItemsChangedSignalMask = 1 << missionItemsChangedSignalIndex,
visualItemsChangedSignalMask = 1 << visualItemsChangedSignalIndex,
waypointLinesChangedSignalMask = 1 << waypointLinesChangedSignalIndex,
};
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -25,16 +25,9 @@
#define MissionItemTest_H
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include <QGeoCoordinate>
/// @file
/// @brief FlightGear HIL Simulation unit tests
///
/// @author Don Gagne <don@thegagnes.com>
/// Unit test for the MissionItem Object
class MissionItemTest : public UnitTest
{
Q_OBJECT
......@@ -43,36 +36,12 @@ public:
MissionItemTest(void);
private slots:
void _test(void);
void _testDefaultValues(void);
private:
typedef struct {
MAV_CMD command;
MAV_FRAME frame;
} ItemInfo_t;
typedef struct {
const char* name;
double value;
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
} ItemExpected_t;
static const ItemInfo_t _rgItemInfo[];
static const ItemExpected_t _rgItemExpected[];
static const FactValue_t _rgFactValuesWaypoint[];
static const FactValue_t _rgFactValuesLoiterUnlim[];
static const FactValue_t _rgFactValuesLoiterTurns[];
static const FactValue_t _rgFactValuesLoiterTime[];
static const FactValue_t _rgFactValuesLand[];
static const FactValue_t _rgFactValuesTakeoff[];
static const FactValue_t _rgFactValuesConditionDelay[];
static const FactValue_t _rgFactValuesDoJump[];
void _testSetGet(void);
void _testSignals(void);
void _testFactSignals(void);
void _testLoadFromStream(void);
void _testLoadFromJson(void);
void _testSaveToJson(void);
};
#endif
......@@ -29,7 +29,6 @@
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "QGCApplication.h"
#include "SimpleMissionItem.h"
QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
......@@ -56,7 +55,7 @@ MissionManager::~MissionManager()
}
void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
{
bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
......@@ -65,12 +64,13 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
int firstIndex = skipFirstItem ? 1 : 0;
for (int i=firstIndex; i<missionItems.count(); i++) {
_missionItems.append(new SimpleMissionItem(*qobject_cast<const SimpleMissionItem*>(missionItems[i])));
MissionItem* item = new MissionItem(*missionItems[i]);
_missionItems.append(item);
MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1));
item->setIsCurrentItem(i == firstIndex);
if (skipFirstItem) {
// Home is in sequence 1, remainder of items start at sequence 1
// Home is in sequence 0, remainder of items start at sequence 1
item->setSequenceNumber(item->sequenceNumber() - 1);
if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
item->setParam1((int)item->param1() - 1);
......@@ -253,8 +253,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
_requestItemRetryCount = 0;
_itemIndicesToRead.removeOne(missionItem.seq);
MissionItem* item = new SimpleMissionItem(_vehicle,
missionItem.seq,
MissionItem* item = new MissionItem(missionItem.seq,
(MAV_CMD)missionItem.command,
(MAV_FRAME)missionItem.frame,
missionItem.param1,
......@@ -268,7 +267,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
missionItem.current,
this);
if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
if (item->command() == MAV_CMD_DO_JUMP) {
// Home is in position 0
item->setParam1((int)item->param1() + 1);
}
......@@ -323,19 +322,19 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
mavlink_message_t messageOut;
mavlink_mission_item_t missionItem;
MissionItem* item = (MissionItem*)_missionItems[missionRequest.seq];
MissionItem* item = _missionItems[missionRequest.seq];
missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionItem.seq = missionRequest.seq;
missionItem.command = item->command();
missionItem.x = item->coordinate().latitude();
missionItem.y = item->coordinate().longitude();
missionItem.z = item->coordinate().altitude();
missionItem.param1 = item->param1();
missionItem.param2 = item->param2();
missionItem.param3 = item->param3();
missionItem.param4 = item->param4();
missionItem.x = item->param5();
missionItem.y = item->param6();
missionItem.z = item->param7();
missionItem.frame = item->frame();
missionItem.current = missionRequest.seq == 0;
missionItem.autocontinue = item->autoContinue();
......@@ -428,17 +427,6 @@ void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
}
}
QmlObjectListModel* MissionManager::copyMissionItems(void)
{
QmlObjectListModel* list = new QmlObjectListModel();
for (int i=0; i<_missionItems.count(); i++) {
list->append(new SimpleMissionItem(*qobject_cast<const SimpleMissionItem*>(_missionItems[i])));
}
return list;
}
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
......
......@@ -30,7 +30,7 @@
#include <QMutex>
#include <QTimer>
#include "QmlObjectListModel.h"
#include "MissionItem.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "LinkInterface.h"
......@@ -48,27 +48,15 @@ public:
MissionManager(Vehicle* vehicle);
~MissionManager();
Q_PROPERTY(bool inProgress READ inProgress NOTIFY inProgressChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems CONSTANT)
Q_PROPERTY(int currentItem READ currentItem NOTIFY currentItemChanged)
// Property accessors
bool inProgress(void);
QmlObjectListModel* missionItems(void) { return &_missionItems; }
const QList<MissionItem*>& missionItems(void) { return _missionItems; }
int currentItem(void) { return _currentMissionItem; }
// C++ methods
void requestMissionItems(void);
/// Writes the specified set of mission items to the vehicle
/// @oaram missionItems Items to send to vehicle
void writeMissionItems(const QmlObjectListModel& missionItems);
/// Returns a copy of the current set of mission items. Caller is responsible for
/// freeing returned object.
QmlObjectListModel* copyMissionItems(void);
/// @param missionItems Items to send to vehicle
void writeMissionItems(const QList<MissionItem*>& missionItems);
/// Error codes returned in error signal
typedef enum {
......@@ -134,7 +122,7 @@ private:
QMutex _dataMutex;
QmlObjectListModel _missionItems;
QList<MissionItem*> _missionItems;
int _currentMissionItem;
};
......
......@@ -24,7 +24,6 @@
#include "MissionManagerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
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 } },
......@@ -46,32 +45,31 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
_mockLink->setMissionItemFailureMode(failureMode);
// Setup our test case data
QmlObjectListModel* list = new QmlObjectListModel();
QList<MissionItem*> missionItems;
// Editor has a home position item on the front, so we do the same
SimpleMissionItem* homeItem = new SimpleMissionItem(NULL /* Vehicle */, this);
homeItem->setHomePositionSpecialCase(true);
homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
MissionItem* homeItem = new MissionItem(NULL /* Vehicle */, this);
homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
homeItem->setCoordinate(QGeoCoordinate(47.3769, 8.549444, 0));
homeItem->setSequenceNumber(0);
list->insert(0, homeItem);
missionItems.append(homeItem);
for (size_t i=0; i<_cTestCases; i++) {
const TestCase_t* testCase = &_rgTestCases[i];
SimpleMissionItem* item = new SimpleMissionItem(NULL /* Vehicle */, list);
MissionItem* missionItem = new MissionItem(this);
QTextStream loadStream(testCase->itemStream, QIODevice::ReadOnly);
QVERIFY(item->load(loadStream));
QVERIFY(missionItem->load(loadStream));
// Mission Manager expects to get 1-base sequence numbers for write
item->setSequenceNumber(item->sequenceNumber() + 1);
missionItem->setSequenceNumber(missionItem->sequenceNumber() + 1);
list->append(item);
missionItems.append(missionItem);
}
// Send the items to the vehicle
_missionManager->writeMissionItems(*list);
_missionManager->writeMissionItems(missionItems);
// writeMissionItems should emit these signals before returning:
// inProgressChanged
......@@ -101,7 +99,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
expectedCount++;
}
QCOMPARE(_missionManager->missionItems()->count(), expectedCount);
QCOMPARE(_missionManager->missionItems().count(), expectedCount);
} else {
// This should be a failed run
......@@ -125,8 +123,6 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
checkExpectedMessageBox();
}
delete list;
list = NULL;
_multiSpyMissionManager->clearAllSignals();
}
......@@ -196,7 +192,7 @@ void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode
cMissionItemsExpected = 0;
}
QCOMPARE(_missionManager->missionItems()->count(), (int)cMissionItemsExpected);
QCOMPARE(_missionManager->missionItems().count(), (int)cMissionItemsExpected);
size_t firstActualItem = 0;
if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
......@@ -214,7 +210,7 @@ void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode
expectedSequenceNumber++;
}
MissionItem* actual = qobject_cast<MissionItem*>(_missionManager->missionItems()->get(actualItemIndex));
MissionItem* actual = _missionManager->missionItems()[actualItemIndex];
qDebug() << "Test case" << testCaseIndex;
QCOMPARE(actual->sequenceNumber(), expectedSequenceNumber);
......
This diff is collapsed.
......@@ -24,39 +24,151 @@
#ifndef SimpleMissionItem_H
#define SimpleMissionItem_H
#include "VisualMissionItem.h"
#include "MissionItem.h"
class SimpleMissionItem : public MissionItem
/// A SimpleMissionItem is used to represent a single MissionItem to the ui.
class SimpleMissionItem : public VisualMissionItem
{
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(Vehicle* vehicle, const MissionItem& missionItem, QObject* parent = NULL);
SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL);
~SimpleMissionItem();
const SimpleMissionItem& operator=(const SimpleMissionItem& other);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return true; }
Q_PROPERTY(QString category READ category NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged)
Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(bool rawEdit READ rawEdit WRITE setRawEdit NOTIFY rawEditChanged) ///< true: raw item editing with all params
Q_PROPERTY(bool relativeAltitude READ relativeAltitude NOTIFY frameChanged)
Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
// These properties are used to display the editing ui
Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY uiModelChanged)
Q_PROPERTY(QmlObjectListModel* comboboxFacts READ comboboxFacts NOTIFY uiModelChanged)
Q_PROPERTY(QmlObjectListModel* textFieldFacts READ textFieldFacts NOTIFY uiModelChanged)
// Property accesors
QString category (void) const;
MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_missionItem._commandFact.cookedValue().toInt(); };
bool friendlyEditAllowed (void) const;
bool homePosition (void) const { return _homePositionSpecialCase; }
bool rawEdit (void) const;
bool showHomePosition (void) const { return _showHomePosition; }
QmlObjectListModel* textFieldFacts (void);
QmlObjectListModel* checkboxFacts (void);
QmlObjectListModel* comboboxFacts (void);
void setRawEdit(bool rawEdit);
void setCommandByIndex(int index);
void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command);
void setHomePositionSpecialCase(bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
void setShowHomePosition(bool showHomePosition);
void setAltDifference (double altDifference);
void setAltPercent (double altPercent);
void setAzimuth (double azimuth);
void setDistance (double distance);
bool load(QTextStream &loadStream);
bool load(const QJsonObject& json, QString& errorString);
bool relativeAltitude(void) { return _missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT; }
static const double defaultAltitude;
MissionItem& missionItem(void) { return _missionItem; }
// Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return true; }
bool isStandaloneCoordinate (void) const final;
bool specifiesCoordinate (void) const final;
QString commandDescription (void) const final;
QString commandName (void) const final;
QGeoCoordinate coordinate (void) const final { return _missionItem.coordinate(); }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return coordinateHasRelativeAltitude(); }
bool exitCoordinateSameAsEntry (void) const final { return true; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate);
bool save (QJsonObject& missionObject, QJsonArray& missionItems, QString& errorString) final;
public slots:
void setDefaultsForCommand(void);
signals:
void commandChanged (int command);
void coordinateChanged (const QGeoCoordinate& coordinate);
void exitCoordinateChanged (const QGeoCoordinate& exitCoordinate);
//void dirtyChanged (bool dirty);
void frameChanged (int frame);
void friendlyEditAllowedChanged (bool friendlyEditAllowed);
void headingDegreesChanged (double heading);
void rawEditChanged (bool rawEdit);
void uiModelChanged (void);
void showHomePositionChanged (bool showHomePosition);
private slots:
void _setDirtyFromSignal(void);
void _sendCommandChanged(void);
void _sendCoordinateChanged(void);
void _sendFrameChanged(void);
void _sendFriendlyEditAllowedChanged(void);
void _sendUiModelChanged(void);
void _syncAltitudeRelativeToHomeToFrame(const QVariant& value);
void _syncFrameToAltitudeRelativeToHome(void);
private:
void _clearParamMetaData(void);
void _connectSignals(void);
void _setupMetaData(void);
private:
MissionItem _missionItem;
bool _rawEdit;
bool _dirty;
bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator
bool _showHomePosition;
Fact _altitudeRelativeToHomeFact;
Fact _supportedCommandFact;
static FactMetaData* _altitudeMetaData;
static FactMetaData* _commandMetaData;
static FactMetaData* _defaultParamMetaData;
static FactMetaData* _frameMetaData;
static FactMetaData* _latitudeMetaData;
static FactMetaData* _longitudeMetaData;
FactMetaData _param1MetaData;
FactMetaData _param2MetaData;
FactMetaData _param3MetaData;
FactMetaData _param4MetaData;
FactMetaData _param5MetaData;
FactMetaData _param6MetaData;
FactMetaData _param7MetaData;
bool _syncingAltitudeRelativeToHomeAndFrame; ///< true: already in a sync signal, prevents signal loop
bool _syncingHeadingDegreesAndParam4; ///< true: already in a sync signal, prevents signal loop
const MissionCommands* _missionCommands;
};
#endif
This diff is collapsed.
/*=====================================================================
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 SimpleMissionItemTest_H
#define SimpleMissionItemTest_H
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include <QGeoCoordinate>
/// Unit test for SimpleMissionItem
class SimpleMissionItemTest : public UnitTest
{
Q_OBJECT
public:
SimpleMissionItemTest(void);
private slots:
void _testSignals(void);
void _testEditorFacts(void);
void _testDefaultValues(void);
private:
typedef struct {
MAV_CMD command;
MAV_FRAME frame;
} ItemInfo_t;
typedef struct {
const char* name;
double value;
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
bool relativeAltCheckbox;
} ItemExpected_t;
static const ItemInfo_t _rgItemInfo[];
static const ItemExpected_t _rgItemExpected[];
static const FactValue_t _rgFactValuesWaypoint[];
static const FactValue_t _rgFactValuesLoiterUnlim[];
static const FactValue_t _rgFactValuesLoiterTurns[];
static const FactValue_t _rgFactValuesLoiterTime[];
static const FactValue_t _rgFactValuesLand[];
static const FactValue_t _rgFactValuesTakeoff[];
static const FactValue_t _rgFactValuesConditionDelay[];
static const FactValue_t _rgFactValuesDoJump[];
};
#endif
/*===================================================================
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 <QStringList>
#include <QDebug>
#include "VisualMissionItem.h"
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "JsonHelper.h"
VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _sequenceNumber(0)
, _isCurrentItem(false)
, _dirty(false)
, _altDifference(0.0)
, _altPercent(0.0)
, _azimuth(0.0)
, _distance(0.0)
{
}
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* parent)
: QObject(parent)
, _vehicle(NULL)
, _sequenceNumber(0)
, _isCurrentItem(false)
, _dirty(false)
, _altDifference(0.0)
, _altPercent(0.0)
, _azimuth(0.0)
, _distance(0.0)
{
*this = other;
}
const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& other)
{
_vehicle = other._vehicle;
setSequenceNumber(other._sequenceNumber);
setIsCurrentItem(other._isCurrentItem);
setDirty(other._dirty);
setAltDifference(other._altDifference);
setAltPercent(other._altPercent);
setAzimuth(other._azimuth);
setDistance(other._distance);
return *this;
}
VisualMissionItem::~VisualMissionItem()
{
}
void VisualMissionItem::setIsCurrentItem(bool isCurrentItem)
{
if (_isCurrentItem != isCurrentItem) {
_isCurrentItem = isCurrentItem;
emit isCurrentItemChanged(isCurrentItem);
}
}
void VisualMissionItem::setDistance(double distance)
{
_distance = distance;
emit distanceChanged(_distance);
}
void VisualMissionItem::setAltDifference(double altDifference)
{
_altDifference = altDifference;
emit altDifferenceChanged(_altDifference);
}
void VisualMissionItem::setAltPercent(double altPercent)
{
_altPercent = altPercent;
emit altPercentChanged(_altPercent);
}
void VisualMissionItem::setAzimuth(double azimuth)
{
_azimuth = azimuth;
emit azimuthChanged(_azimuth);
}
void VisualMissionItem::setSequenceNumber (int sequenceNumber)
{
if (_sequenceNumber != sequenceNumber) {
_sequenceNumber = sequenceNumber;
emit sequenceNumberChanged(_sequenceNumber);
}
}
/*=====================================================================
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 VisualMissionItem_H
#define VisualMissionItem_H
#include <QObject>
#include <QString>
#include <QtQml>
#include <QTextStream>
#include <QJsonObject>
#include <QGeoCoordinate>
#include "QGCMAVLink.h"
#include "QGC.h"
#include "MavlinkQmlSingleton.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MissionCommands.h"
// Abstract base class for all Simple and Complex visual mission objects.
class VisualMissionItem : public QObject
{
Q_OBJECT
public:
VisualMissionItem(Vehicle* vehicle, QObject* parent = NULL);
VisualMissionItem(const VisualMissionItem& other, QObject* parent = NULL);
~VisualMissionItem();
const VisualMissionItem& operator=(const VisualMissionItem& other);
// The following properties are calulated/set by the MissionControll recalc methods
Q_PROPERTY(double altDifference READ altDifference WRITE setAltDifference NOTIFY altDifferenceChanged) ///< Change in altitude from previous waypoint
Q_PROPERTY(double altPercent READ altPercent WRITE setAltPercent NOTIFY altPercentChanged) ///< Percent of total altitude change in mission altitude
Q_PROPERTY(double azimuth READ azimuth WRITE setAzimuth NOTIFY azimuthChanged) ///< Azimuth to previous waypoint
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint
// Visual mission items have two coordinates associated with them:
/// This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
/// @return true: coordinate.latitude is relative to home altitude
Q_PROPERTY(bool coordinateHasRelativeAltitude READ coordinateHasRelativeAltitude NOTIFY coordinateHasRelativeAltitudeChanged)
/// This is the exit point for a waypoint line coming out of the item.
Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged)
/// @return true: coordinate.latitude is relative to home altitude
Q_PROPERTY(bool exitCoordinateHasRelativeAltitude READ exitCoordinateHasRelativeAltitude NOTIFY exitCoordinateHasRelativeAltitudeChanged)
/// @return true: exitCoordinate and coordinate are the same value
Q_PROPERTY(bool exitCoordinateSameAsEntry READ exitCoordinateSameAsEntry NOTIFY exitCoordinateSameAsEntry)
// General properties associated with all types of visual mission items
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandDescriptionChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandNameChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< Item is dirty and requires save/send
Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged)
Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY specifiesCoordinateChanged) ///< Item is associated with a coordinate position
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate NOTIFY isStandaloneCoordinateChanged) ///< Wayoint line does not go through item
Q_PROPERTY(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) ///< Simple or Complex MissionItem
/// List of child mission items. Child mission item are subsequent mision items which do not specify a coordinate. They
/// are shown next to the exitCoordinate indidcator in the ui.
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
// Property accesors
double altDifference (void) const { return _altDifference; }
double altPercent (void) const { return _altPercent; }
double azimuth (void) const { return _azimuth; }
double distance (void) const { return _distance; }
bool isCurrentItem (void) const { return _isCurrentItem; }
int sequenceNumber (void) const { return _sequenceNumber; }
QmlObjectListModel* childItems(void) { return &_childItems; }
void setIsCurrentItem (bool isCurrentItem);
void setAltDifference (double altDifference);
void setAltPercent (double altPercent);
void setAzimuth (double azimuth);
void setDistance (double distance);
void setSequenceNumber (int sequenceNumber);
Vehicle* vehicle(void) { return _vehicle; }
// Pure virtuals which must be provides by derived classes
virtual bool dirty (void) const = 0;
virtual bool isSimpleItem (void) const = 0;
virtual bool isStandaloneCoordinate (void) const = 0;
virtual bool specifiesCoordinate (void) const = 0;
virtual QString commandDescription (void) const = 0;
virtual QString commandName (void) const = 0;
virtual QGeoCoordinate coordinate (void) const = 0;
virtual QGeoCoordinate exitCoordinate (void) const = 0;
virtual bool coordinateHasRelativeAltitude (void) const = 0;
virtual bool exitCoordinateHasRelativeAltitude (void) const = 0;
virtual bool exitCoordinateSameAsEntry (void) const = 0;
virtual void setDirty (bool dirty) = 0;
virtual void setCoordinate (const QGeoCoordinate& coordinate) = 0;
/// Save the item in Json format
/// @param missionObject Top level object for entire mission file
/// @param missionItems Array of mission items
/// @return false: save failed, errorString set
virtual bool save(QJsonObject& missionObject, QJsonArray& missionItems, QString& errorString) = 0;
signals:
void altDifferenceChanged (double altDifference);
void altPercentChanged (double altPercent);
void azimuthChanged (double azimuth);
void commandDescriptionChanged (void);
void commandNameChanged (void);
void coordinateChanged (const QGeoCoordinate& coordinate);
void exitCoordinateChanged (const QGeoCoordinate& exitCoordinate);
void dirtyChanged (bool dirty);
void distanceChanged (double distance);
void isCurrentItemChanged (bool isCurrentItem);
void sequenceNumberChanged (int sequenceNumber);
void isSimpleItemChanged (bool isSimpleItem);
void specifiesCoordinateChanged (void);
void isStandaloneCoordinateChanged (void);
void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude);
void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude);
void exitCoordinateSameAsEntry (bool exitCoordinateSameAsEntry);
protected:
Vehicle* _vehicle;
int _sequenceNumber;
bool _isCurrentItem;
bool _dirty;
double _altDifference; ///< Difference in altitude from previous waypoint
double _altPercent; ///< Percent of total altitude change in mission
double _azimuth; ///< Azimuth to previous waypoint
double _distance; ///< Distance to previous waypoint
/// This is used to reference any subsequent mission items which do not specify a coordinate.
QmlObjectListModel _childItems;
};
#endif
......@@ -82,14 +82,14 @@ Rectangle {
}
MenuSeparator {
visible: !missionItem.simpleItem
visible: missionItem.isSimpleItem
}
MenuItem {
text: "Show all values"
checkable: true
checked: missionItem.rawEdit
visible: !missionItem.simpleItem
visible: missionItem.isSimpleItem
onTriggered: {
if (missionItem.rawEdit) {
......@@ -114,7 +114,7 @@ Rectangle {
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.left: label.right
anchors.right: hamburger.left
visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.simpleItem
visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem
text: missionItem.commandName
Component {
......@@ -130,9 +130,9 @@ Rectangle {
QGCLabel {
anchors.fill: commandPicker
visible: missionItem.sequenceNumber == 0 || !missionItem.isCurrentItem || !missionItem.simpleItem
visible: missionItem.sequenceNumber == 0 || !missionItem.isCurrentItem || !missionItem.isSimpleItem
verticalAlignment: Text.AlignVCenter
text: missionItem.sequenceNumber == 0 ? "Home Position" : (missionItem.simpleItem ? missionItem.commandName : "Survey")
text: missionItem.sequenceNumber == 0 ? "Home Position" : (missionItem.isSimpleItem ? missionItem.commandName : "Survey")
color: _outerTextColor
}
......@@ -142,7 +142,7 @@ Rectangle {
anchors.topMargin: _margin
anchors.left: parent.left
anchors.top: commandPicker.bottom
sourceComponent: missionItem.simpleItem ? simpleMissionItemEditor : complexMissionItemEditor
sourceComponent: missionItem.isSimpleItem ? simpleMissionItemEditor : complexMissionItemEditor
/// How wide the loaded component should be
property real availableWidth: _root.width - (_margin * 2)
......
......@@ -32,6 +32,7 @@
#include "LinkManagerTest.h"
#include "MessageBoxTest.h"
#include "MissionItemTest.h"
#include "SimpleMissionItemTest.h"
#include "MissionControllerTest.h"
#include "MissionManagerTest.h"
#include "RadioConfigTest.h"
......@@ -47,6 +48,7 @@ UT_REGISTER_TEST(LinkManagerTest)
UT_REGISTER_TEST(MavlinkLogTest)
UT_REGISTER_TEST(MessageBoxTest)
UT_REGISTER_TEST(MissionItemTest)
UT_REGISTER_TEST(SimpleMissionItemTest)
UT_REGISTER_TEST(MissionControllerTest)
UT_REGISTER_TEST(MissionManagerTest)
UT_REGISTER_TEST(RadioConfigTest)
......
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