Commit 51bfac2f authored by Don Gagne's avatar Don Gagne

Planned Home Position support

Also additional major Mission usability changes
parent 6796b7a2
......@@ -51,7 +51,7 @@ Map {
readonly property real maxZoomLevel: 20
zoomLevel: 18
center: QGroundControl.defaultMapPosition
center: QGroundControl.lastKnownHomePosition
gesture.flickDeceleration: 3000
gesture.activeGestures: MapGestureArea.ZoomGesture | MapGestureArea.PanGesture | MapGestureArea.FlickGesture
......
......@@ -35,41 +35,13 @@ import QGroundControl.Controls 1.0
MapItemView {
id: _root
property var itemDragger ///< Set to item drag control if you want to support drag
delegate: MissionItemIndicator {
id: itemIndicator
coordinate: object.coordinate
visible: object.specifiesCoordinate && (!object.homePosition || object.homePositionValid)
visible: object.specifiesCoordinate && (index != 0 || object.showHomePosition)
z: QGroundControl.zOrderMapItems
missionItem: object
onClicked: setCurrentItem(object.sequenceNumber)
Connections {
target: object
onIsCurrentItemChanged: {
if (isCurrentItem) {
if (_root.itemDragger) {
// Setup our drag item
if (object.sequenceNumber != 0) {
_root.itemDragger.visible = true
_root.itemDragger.missionItem = Qt.binding(function() { return object })
_root.itemDragger.missionItemIndicator = Qt.binding(function() { return itemIndicator })
} else {
_root.itemDragger.clearItem()
}
}
// Zoom the map and move to the new position
_root.parent.zoomLevel = _root.parent.maxZoomLevel
_root.parent.latitude = object.coordinate.latitude
_root.parent.longitude = object.coordinate.longitude
}
}
}
// These are the non-coordinate child mission items attached to this item
Row {
anchors.top: parent.top
......
......@@ -30,6 +30,10 @@ import QGroundControl.Palette 1.0
/// The MissionLineView control is used to add lines between mission items
MapItemView {
id: _root
property bool homePositionValid: true ///< true: show home position, false: don't show home position
delegate: MapPolyline {
line.width: 3
line.color: "#be781c" // Hack, can't get palette to work in here
......
......@@ -65,10 +65,6 @@ QGCView {
property bool _firstVehiclePosition: true
property var activeVehiclePosition: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var liveHomePosition: controller.liveHomePosition
property var liveHomePositionAvailable: controller.liveHomePositionAvailable
property var homePosition: _defaultVehicleCoordinate
property bool _syncInProgress: _activeVehicle ? _activeVehicle.missionManager.inProgress : false
Component.onCompleted: updateMapToVehiclePosition()
......@@ -112,27 +108,24 @@ QGCView {
/// Fix the map viewport to the current mission items. We don't fit the home position in this process.
function fitViewportToMissionItems() {
if (_missionItems.count <= 1) {
return
}
var missionItem = _missionItems.get(1)
var missionItem = _missionItems.get(0)
var north = normalizeLat(missionItem.coordinate.latitude)
var south = north
var east = normalizeLon(missionItem.coordinate.longitude)
var west = east
for (var i=2; i<_missionItems.count; i++) {
for (var i=1; i<_missionItems.count; i++) {
missionItem = _missionItems.get(i)
var lat = normalizeLat(missionItem.coordinate.latitude)
var lon = normalizeLon(missionItem.coordinate.longitude)
if (missionItem.specifiesCoordinate && !missionItem.standaloneCoordinate) {
var lat = normalizeLat(missionItem.coordinate.latitude)
var lon = normalizeLon(missionItem.coordinate.longitude)
north = Math.max(north, lat)
south = Math.min(south, lat)
east = Math.max(east, lon)
west = Math.min(west, lon)
north = Math.max(north, lat)
south = Math.min(south, lat)
east = Math.max(east, lon)
west = Math.min(west, lon)
}
}
editorMap.visibleRegion = QtPositioning.rectangle(QtPositioning.coordinate(north - 90.0, west - 180.0), QtPositioning.coordinate(south - 90.0, east - 180.0))
......@@ -143,6 +136,7 @@ QGCView {
Component.onCompleted: {
start(true /* editMode */)
setCurrentItem(0)
}
/*
......@@ -241,13 +235,11 @@ QGCView {
anchors.fill: parent
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 (false /*homePositionManagerButton.checked*/) {
//offlineHomePosition = coordinate
} else if (addMissionItemsButton.checked) {
if (addMissionItemsButton.checked) {
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)
var index = controller.insertMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index)
} else {
......@@ -318,7 +310,7 @@ QGCView {
MissionItemIndicator {
id: itemIndicator
coordinate: object.coordinate
visible: object.specifiesCoordinate && (!object.homePosition || object.homePositionValid)
visible: object.specifiesCoordinate
z: QGroundControl.zOrderMapItems
missionItem: object
......@@ -329,13 +321,9 @@ QGCView {
if (object.isCurrentItem && itemIndicator.visible) {
if (object.specifiesCoordinate) {
// Setup our drag item
if (object.sequenceNumber != 0) {
itemDragger.visible = true
itemDragger.missionItem = Qt.binding(function() { return object })
itemDragger.missionItemIndicator = Qt.binding(function() { return itemIndicator })
} else {
itemDragger.clearItem()
}
}
}
}
......@@ -379,7 +367,6 @@ QGCView {
anchors.bottom: parent.bottom
anchors.right: parent.right
width: _rightPanelWidth
visible: _missionItems.count > 1
opacity: _rightPanelOpacity
z: QGroundControl.zOrderTopMost
......@@ -399,13 +386,11 @@ QGCView {
property real _maxItemHeight: 0
delegate:
MissionItemEditor {
delegate: MissionItemEditor {
missionItem: object
width: parent.width
readOnly: object.sequenceNumber == 0
visible: !readOnly || object.homePositionValid
qgcView: _root
readOnly: false
onClicked: setCurrentItem(object.sequenceNumber)
......@@ -423,6 +408,8 @@ QGCView {
controller.insertMissionItem(editorMap.center, i)
setCurrentItem(i)
}
onMoveHomeToMapCenter: controller.missionItems.get(0).coordinate = editorMap.center
}
} // ListView
} // Item - Mission Item editor
......@@ -485,12 +472,11 @@ QGCView {
spacing: ScreenTools.defaultFontPixelWidth
QGCButton {
text: "Home"
enabled: liveHomePositionAvailable
text: "Home"
onClicked: {
centerMapButton.hideDropDown()
editorMap.center = liveHomePosition
editorMap.center = controller.missionItems.get(0).coordinate
}
}
......@@ -582,7 +568,6 @@ QGCView {
currentMissionItem: _currentMissionItem
missionItems: controller.missionItems
expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2)
homePositionValid: liveHomePositionAvailable
}
} // FlightMap
} // Item - split view container
......
......@@ -32,7 +32,6 @@ Rectangle {
property var currentMissionItem ///< Mission item to display status for
property var missionItems ///< List of all available mission items
property real expandedWidth ///< Width of control when expanded
property bool homePositionValid: false /// true: home position in missionItems[0] is valid
width: _expanded ? expandedWidth : _collapsedWidth
height: expandLabel.y + expandLabel.height + _margins
......@@ -49,7 +48,7 @@ Rectangle {
property real _altDifference: _currentMissionItem ? _currentMissionItem.altDifference : -1
property real _azimuth: _currentMissionItem ? _currentMissionItem.azimuth : -1
property real _isHomePosition: _currentMissionItem ? _currentMissionItem.homePosition : false
property bool _statusValid: _distance != -1 && ((_isHomePosition && homePositionValid) || !_isHomePosition)
property bool _statusValid: _distance != -1
property string _distanceText: _statusValid ? Math.round(_distance) + " meters" : ""
property string _altText: _statusValid ? Math.round(_altDifference) + " meters" : ""
property string _azimuthText: _statusValid ? Math.round(_azimuth) : ""
......@@ -115,9 +114,7 @@ Rectangle {
property real availableHeight: height - ScreenTools.smallFontPixelHeight - indicator.height
// If home position is not valid we are graphing relative based on a home alt of 0. Because of this
// we cannot graph absolute altitudes since we have no basis for comparison against the relative values.
property bool graphAbsolute: homePositionValid
property bool graphAbsolute: true
MissionItemIndexLabel {
id: indicator
......
......@@ -6,11 +6,21 @@
"comment": "MAV_CMD_NAV_LAST: Used for fake home position waypoint",
"id": 95,
"rawName": "HomeRaw",
"friendlyName": "Home",
"description": "Home Position",
"description": "Home Position",
"friendlyName": "Home Position",
"description": "Planned home position for mission.",
"specifiesCoordinate": true,
"friendlyEdit": true
"friendlyEdit": true,
"category": "Basic",
"param5": {
"label": "Latitude:",
"default": 37.803784,
"decimalPlaces": 7
},
"param6": {
"label": "Longitude:",
"default": -122.462276,
"decimalPlaces": 7
}
},
{
"id": 16,
......
This diff is collapsed.
......@@ -42,8 +42,6 @@ public:
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool liveHomePositionAvailable READ liveHomePositionAvailable NOTIFY liveHomePositionAvailableChanged)
Q_PROPERTY(QGeoCoordinate liveHomePosition READ liveHomePosition NOTIFY liveHomePositionChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_INVOKABLE void start(bool editMode);
......@@ -61,16 +59,12 @@ public:
QmlObjectListModel* missionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; }
QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; }
bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync);
signals:
void missionItemsChanged(void);
void waypointLinesChanged(void);
void liveHomePositionAvailableChanged(bool homePositionAvailable);
void liveHomePositionChanged(const QGeoCoordinate& homePosition);
void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void);
......@@ -95,25 +89,34 @@ private:
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _autoSyncSend(void);
void _setupMissionItems(bool loadFromVehicle, bool forceLoad);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
void _calcPrevWaypointValues(bool homePositionValid, double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
void _calcPrevWaypointValues(double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
bool _findLastAltitude(double* lastAltitude);
bool _findLastAcceptanceRadius(double* lastAcceptanceRadius);
void _addPlannedHomePosition(bool addToCenter);
double _normalizeLat(double lat);
double _normalizeLon(double lon);
#ifndef __mobile__
bool _loadJsonMissionFile(const QByteArray& bytes, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QString& errorString);
#endif
private:
bool _editMode;
QmlObjectListModel* _missionItems;
QmlObjectListModel _waypointLines;
Vehicle* _activeVehicle;
bool _liveHomePositionAvailable;
QGeoCoordinate _liveHomePosition;
bool _autoSync;
bool _firstItemsFromVehicle;
bool _missionItemsRequested;
bool _queuedSend;
static const char* _settingsGroup;
static const char* _settingsGroup;
static const char* _jsonVersionKey;
static const char* _jsonGroundStationKey;
static const char* _jsonMavAutopilotKey;
static const char* _jsonItemsKey;
static const char* _jsonPlannedHomePositionKey;
};
#endif
......@@ -59,14 +59,11 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
void homePositionValidChanged(bool homePostionValid);
// MissionItem signals
_rgMissionItemSignals[coordinateChangedSignalIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
_rgMissionItemSignals[homePositionValidChangedSignalIndex] = SIGNAL(homePositionValidChanged(bool));
_rgMissionItemSignals[coordinateChangedSignalIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
// MissionController signals
_rgMissionControllerSignals[missionItemsChangedSignalIndex] = SIGNAL(missionItemsChanged());
_rgMissionControllerSignals[waypointLinesChangedSignalIndex] = SIGNAL(waypointLinesChanged());
_rgMissionControllerSignals[liveHomePositionAvailableChangedSignalIndex] = SIGNAL(liveHomePositionAvailableChanged(bool));
_rgMissionControllerSignals[liveHomePositionChangedSignalIndex] = SIGNAL(liveHomePositionChanged(const QGeoCoordinate&));
_rgMissionControllerSignals[missionItemsChangedSignalIndex] = SIGNAL(missionItemsChanged());
_rgMissionControllerSignals[waypointLinesChangedSignalIndex] = SIGNAL(waypointLinesChanged());
if (!_missionController) {
startController = true;
......@@ -83,7 +80,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
}
// All signals should some through on start
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
_multiSpyMissionController->clearAllSignals();
QmlObjectListModel* missionItems = _missionController->missionItems();
......@@ -96,7 +93,6 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
QVERIFY(homeItem);
QCOMPARE(homeItem->homePosition(), true);
QCOMPARE(homeItem->homePositionValid(), false);
// Home should have no children
QCOMPARE(homeItem->childItems()->count(), 0);
......@@ -106,9 +102,6 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
QVERIFY(waypointLines);
QCOMPARE(waypointLines->count(), 0);
// Should not have home position yet
QCOMPARE(_missionController->liveHomePositionAvailable(), false);
// AutoSync should be off by default
QCOMPARE(_missionController->autoSync(), false);
}
......@@ -120,44 +113,12 @@ void MissionControllerTest::_testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType)
// FYI: A significant amount of empty vehicle testing is in _initForFirmwareType since that
// sets up an empty vehicle
// APM stack doesn't support HOME_POSITION yet
bool expectedHomePositionValid = firmwareType == MAV_AUTOPILOT_PX4 ? true : false;
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
QVERIFY(homeItem);
_setupMissionItemSignals(homeItem);
if (expectedHomePositionValid) {
// Wait for the home position to show up
if (!_missionController->liveHomePositionAvailable()) {
QVERIFY(_multiSpyMissionController->waitForSignalByIndex(liveHomePositionAvailableChangedSignalIndex, 2000));
QCOMPARE(_multiSpyMissionController->pullBoolFromSignalIndex(liveHomePositionAvailableChangedSignalIndex), true);
}
if (!homeItem->homePositionValid()) {
QVERIFY(_multiSpyMissionItem->waitForSignalByIndex(homePositionValidChangedSignalIndex, 2000));
QCOMPARE(_multiSpyMissionItem->pullBoolFromSignalIndex(homePositionValidChangedSignalIndex), true);
}
// Once the home position shows up we get a number of addititional signals
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(liveHomePositionChangedSignalMask | liveHomePositionAvailableChangedSignalMask | waypointLinesChangedSignalMask), true);
QCOMPARE(_multiSpyMissionController->checkSignalByMask(liveHomePositionChangedSignalMask | liveHomePositionAvailableChangedSignalMask), true);
QCOMPARE(_multiSpyMissionController->checkSignalByMask(waypointLinesChangedSignalMask), false);
QCOMPARE(_multiSpyMissionItem->checkSignalByMask(homePositionValidChangedSignalMask), true);
_multiSpyMissionController->clearAllSignals();
_multiSpyMissionItem->clearAllSignals();
}
QCOMPARE(homeItem->homePositionValid(), expectedHomePositionValid);
QCOMPARE(_missionController->liveHomePositionAvailable(), expectedHomePositionValid);
QCOMPARE(_missionController->liveHomePosition().isValid(), expectedHomePositionValid);
}
void MissionControllerTest::_testEmptyVehiclePX4(void)
......@@ -194,16 +155,14 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QCOMPARE(homeItem->childItems()->count(), firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 1 : 0);
QCOMPARE(item->childItems()->count(), 0);
int expectedLineCount;
if (homeItem->homePositionValid()) {
expectedLineCount = 1;
} else {
expectedLineCount = 0;
}
#if 0
// This needs re-work
int expectedLineCount = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : 1;
QmlObjectListModel* waypointLines = _missionController->waypointLines();
QVERIFY(waypointLines);
QCOMPARE(waypointLines->count(), expectedLineCount);
#endif
}
void MissionControllerTest::_testAddWayppointAPM(void)
......
......@@ -61,13 +61,11 @@ private:
enum {
coordinateChangedSignalIndex = 0,
homePositionValidChangedSignalIndex,
missionItemMaxSignalIndex
};
enum {
coordinateChangedSignalMask = 1 << coordinateChangedSignalIndex,
homePositionValidChangedSignalMask = 1 << homePositionValidChangedSignalIndex,
missionItemMaxSignalMask = 1 << missionItemMaxSignalIndex,
};
......@@ -76,16 +74,12 @@ private:
enum {
missionItemsChangedSignalIndex = 0,
waypointLinesChangedSignalIndex,
liveHomePositionAvailableChangedSignalIndex,
liveHomePositionChangedSignalIndex,
missionControllerMaxSignalIndex
};
enum {
missionItemsChangedSignalMask = 1 << missionItemsChangedSignalIndex,
waypointLinesChangedSignalMask = 1 << waypointLinesChangedSignalIndex,
liveHomePositionAvailableChangedSignalMask = 1 << liveHomePositionAvailableChangedSignalIndex,
liveHomePositionChangedSignalMask = 1 << liveHomePositionChangedSignalIndex,
};
MultiSignalSpy* _multiSpyMissionController;
......
......@@ -26,6 +26,7 @@ This file is part of the QGROUNDCONTROL project
#include "MissionItem.h"
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "JsonHelper.h"
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
......@@ -38,6 +39,18 @@ FactMetaData* MissionItem::_frameMetaData = NULL;
FactMetaData* MissionItem::_latitudeMetaData = NULL;
FactMetaData* MissionItem::_longitudeMetaData = NULL;
const char* MissionItem::_itemType = "missionItem";
const char* MissionItem::_jsonTypeKey = "type";
const char* MissionItem::_jsonIdKey = "id";
const char* MissionItem::_jsonFrameKey = "frame";
const char* MissionItem::_jsonCommandKey = "command";
const char* MissionItem::_jsonParam1Key = "param1";
const char* MissionItem::_jsonParam2Key = "param2";
const char* MissionItem::_jsonParam3Key = "param3";
const char* MissionItem::_jsonParam4Key = "param4";
const char* MissionItem::_jsonAutoContinueKey = "autoContinue";
const char* MissionItem::_jsonCoordinateKey = "coordinate";
struct EnumInfo_s {
const char * label;
MAV_FRAME frame;
......@@ -86,7 +99,7 @@ MissionItem::MissionItem(Vehicle* vehicle, QObject* parent)
, _azimuth(0.0)
, _distance(0.0)
, _homePositionSpecialCase(false)
, _homePositionValid(false)
, _showHomePosition(false)
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _autoContinueFact (0, "AutoContinue", FactMetaData::valueTypeUint32)
, _commandFact (0, "", FactMetaData::valueTypeUint32)
......@@ -147,7 +160,7 @@ MissionItem::MissionItem(Vehicle* vehicle,
, _azimuth(0.0)
, _distance(0.0)
, _homePositionSpecialCase(false)
, _homePositionValid(false)
, _showHomePosition(false)
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _commandFact (0, "", FactMetaData::valueTypeUint32)
, _frameFact (0, "", FactMetaData::valueTypeUint32)
......@@ -205,7 +218,7 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
, _azimuth(0.0)
, _distance(0.0)
, _homePositionSpecialCase(false)
, _homePositionValid(false)
, _showHomePosition(false)
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _commandFact (0, "", FactMetaData::valueTypeUint32)
, _frameFact (0, "", FactMetaData::valueTypeUint32)
......@@ -252,7 +265,7 @@ const MissionItem& MissionItem::operator=(const MissionItem& other)
setAzimuth(other._azimuth);
setDistance(other._distance);
setHomePositionSpecialCase(other._homePositionSpecialCase);
setHomePositionValid(other._homePositionValid);
setShowHomePosition(other._showHomePosition);
_syncFrameToAltitudeRelativeToHome();
......@@ -360,22 +373,21 @@ MissionItem::~MissionItem()
{
}
void MissionItem::save(QTextStream &saveStream)
void MissionItem::save(QJsonObject& json)
{
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <autoContinue> <DESCRIPTION>
// as documented here: http://qgroundcontrol.org/waypoint_protocol
saveStream << sequenceNumber() << "\t"
<< isCurrentItem() << "\t"
<< frame() << "\t"
<< command() << "\t"
<< QString("%1").arg(param1(), 0, 'g', 18) << "\t"
<< QString("%1").arg(param2(), 0, 'g', 18) << "\t"
<< QString("%1").arg(param3(), 0, 'g', 18) << "\t"
<< QString("%1").arg(param4(), 0, 'g', 18) << "\t"
<< QString("%1").arg(param5(), 0, 'g', 18) << "\t"
<< QString("%1").arg(param6(), 0, 'g', 18) << "\t"
<< QString("%1").arg(param7(), 0, 'g', 18) << "\t"
<< this->autoContinue() << "\r\n";
json[_jsonTypeKey] = _itemType;
json[_jsonIdKey] = sequenceNumber();
json[_jsonFrameKey] = frame();
json[_jsonCommandKey] = command();
json[_jsonParam1Key] = param1();
json[_jsonParam2Key] = param2();
json[_jsonParam3Key] = param3();
json[_jsonParam4Key] = param4();
json[_jsonAutoContinueKey] = autoContinue();
QJsonArray coordinateArray;
coordinateArray << param5() << param6() << param7();
json[_jsonCoordinateKey] = coordinateArray;
}
bool MissionItem::load(QTextStream &loadStream)
......@@ -396,9 +408,45 @@ bool MissionItem::load(QTextStream &loadStream)
setAutoContinue(wpParams[11].toInt() == 1 ? true : false);
return true;
}
return false;
}
bool MissionItem::load(const QJsonObject& json, QString& errorString)
{
QStringList requiredKeys;
requiredKeys << _jsonTypeKey << _jsonIdKey << _jsonFrameKey << _jsonCommandKey <<
_jsonParam1Key << _jsonParam2Key << _jsonParam3Key << _jsonParam4Key <<
_jsonAutoContinueKey << _jsonCoordinateKey;
if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) {
return false;
}
if (json[_jsonTypeKey] != _itemType) {
errorString = QString("type found: %1 must be: %2").arg(json[_jsonTypeKey].toString()).arg(_itemType);
return false;
}
QGeoCoordinate coordinate;
if (!JsonHelper::toQGeoCoordinate(json[_jsonCoordinateKey], coordinate, true /* altitudeRequired */, errorString)) {
return false;
}
setCoordinate(coordinate);
setIsCurrentItem(false);
setSequenceNumber(json[_jsonIdKey].toInt());
setFrame((MAV_FRAME)json[_jsonFrameKey].toInt());
setCommand((MAV_CMD)json[_jsonCommandKey].toInt());
setParam1(json[_jsonParam1Key].toDouble());
setParam2(json[_jsonParam2Key].toDouble());
setParam3(json[_jsonParam3Key].toDouble());
setParam4(json[_jsonParam4Key].toDouble());
setAutoContinue(json[_jsonAutoContinueKey].toBool());
return true;
}
void MissionItem::setSequenceNumber(int sequenceNumber)
{
......@@ -562,7 +610,12 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
} else {
_clearParamMetaData();
MAV_CMD command = (MAV_CMD)this->command();
MAV_CMD command;
if (_homePositionSpecialCase) {
command = MAV_CMD_NAV_LAST;
} else {
command = (MAV_CMD)this->command();
}
Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact };
FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
......@@ -601,7 +654,7 @@ QmlObjectListModel* MissionItem::checkboxFacts(void)
if (rawEdit()) {
model->append(&_autoContinueFact);
} else if (specifiesCoordinate()) {
} else if (specifiesCoordinate() && !_homePositionSpecialCase) {
model->append(&_altitudeRelativeToHomeFact);
}
......@@ -619,7 +672,12 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact };
FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
MAV_CMD command = (MAV_CMD)this->command();
MAV_CMD command;
if (_homePositionSpecialCase) {
command = MAV_CMD_NAV_LAST;
} else {
command = (MAV_CMD)this->command();
}
for (int i=1; i<=7; i++) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _missionCommands->getMavCmdInfo(command, _vehicle)->paramInfoMap();
......@@ -663,9 +721,9 @@ bool MissionItem::friendlyEditAllowed(void) const
if (specifiesCoordinate()) {
return frame() == MAV_FRAME_GLOBAL || frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT;
} else {
return frame() == MAV_FRAME_MISSION;
}
return true;
}
return false;
......@@ -701,12 +759,6 @@ void MissionItem::_setDirtyFromSignal(void)
setDirty(true);
}
void MissionItem::setHomePositionValid(bool homePositionValid)
{
_homePositionValid = homePositionValid;
emit homePositionValidChanged(_homePositionValid);
}
void MissionItem::setDistance(double distance)
{
_distance = distance;
......@@ -808,3 +860,11 @@ QString MissionItem::category(void) const
{
return qgcApp()->toolbox()->missionCommands()->categoryFromCommand(command());
}
void MissionItem::setShowHomePosition(bool showHomePosition)
{
if (showHomePosition != _showHomePosition) {
_showHomePosition = showHomePosition;
emit showHomePositionChanged(_showHomePosition);
}
}
......@@ -28,6 +28,7 @@
#include <QString>
#include <QtQml>
#include <QTextStream>
#include <QJsonObject>
#include <QGeoCoordinate>
#include "QGCMAVLink.h"
......@@ -81,13 +82,13 @@ public:
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 homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator