Commit 85e0c56a authored by DonLakeFlyer's avatar DonLakeFlyer

Simple mission terrain support

parent 98071529
......@@ -97,7 +97,7 @@ bool JsonHelper::validateKeyTypes(const QJsonObject& jsonObject, const QStringLi
QString valueKey = keys[i];
if (jsonObject.contains(valueKey)) {
const QJsonValue& jsonValue = jsonObject[valueKey];
if (types[i] == QJsonValue::Null && jsonValue.type() == QJsonValue::Double) {
if (jsonValue.type() == QJsonValue::Null && types[i] == QJsonValue::Double) {
// Null type signals a NaN on a double value
continue;
}
......
......@@ -106,7 +106,7 @@ public:
static bool parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString, QString valueName = QString());
/// Returns NaN if the value is null, or it not the double value
/// Returns NaN if the value is null, or if not, the double value
static double possibleNaNJsonValue(const QJsonValue& value);
static const char* jsonVersionKey;
......
......@@ -343,13 +343,13 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
}
}
newItem->setDefaultsForCommand();
if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
double prevAltitude;
MAV_FRAME prevFrame;
if (newItem->specifiesAltitude()) {
double prevAltitude;
int prevAltitudeMode;
if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
newItem->missionItem().setFrame(prevFrame);
newItem->missionItem().setParam7(prevAltitude);
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
}
}
newItem->setMissionFlightStatus(_missionFlightStatus);
......@@ -372,12 +372,12 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
newItem->setDefaultsForCommand();
newItem->setCoordinate(coordinate);
double prevAltitude;
MAV_FRAME prevFrame;
double prevAltitude;
int prevAltitudeMode;
if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
newItem->missionItem().setFrame(prevFrame);
newItem->missionItem().setParam7(prevAltitude);
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
}
_visualItems->insert(i, newItem);
......@@ -924,6 +924,18 @@ bool MissionController::loadTextFile(QFile& file, QString& errorString)
return true;
}
bool MissionController::readyForSaveSend(void) const
{
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
if (!visualItem->readyForSave()) {
return false;
}
}
return true;
}
void MissionController::save(QJsonObject& json)
{
json[JsonHelper::jsonVersionKey] = _missionFileVersion;
......@@ -1648,11 +1660,11 @@ void MissionController::_inProgressChanged(bool inProgress)
emit syncInProgressChanged(inProgress);
}
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
{
bool found = false;
double foundAltitude;
MAV_FRAME foundFrame;
int foundAltitudeMode;
if (newIndex > _visualItems->count()) {
return false;
......@@ -1665,9 +1677,9 @@ bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude
if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
if (visualItem->isSimpleItem()) {
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
foundAltitude = simpleItem->exitCoordinate().altitude();
foundFrame = simpleItem->missionItem().frame();
if (simpleItem->specifiesAltitude()) {
foundAltitude = simpleItem->altitude()->rawValue().toDouble();
foundAltitudeMode = simpleItem->altitudeMode();
found = true;
break;
}
......@@ -1677,7 +1689,7 @@ bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude
if (found) {
*prevAltitude = foundAltitude;
*prevFrame = foundFrame;
*prevAltitudeMode = foundAltitudeMode;
}
return found;
......
......@@ -118,6 +118,10 @@ public:
/// @param sequenceNumber - index for new item, -1 to clear current item
Q_INVOKABLE void setCurrentPlanViewIndex(int sequenceNumber, bool force);
/// Determines if the mission has all data needed to be saved or sent to the vehicle. Currently the only case where this
/// would return false is when it is still waiting on terrain data to determine correct altitudes.
bool readyForSaveSend(void) const;
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
......@@ -218,7 +222,7 @@ private:
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
static double _calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem);
bool _findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame);
bool _findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode);
static double _normalizeLat(double lat);
static double _normalizeLon(double lon);
void _addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter);
......
......@@ -47,10 +47,14 @@ public:
/// Should be called immediately upon Component.onCompleted.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view
Q_INVOKABLE virtual void start(bool editMode);
Q_INVOKABLE void start(bool editMode);
/// Starts the controller using a single static active vehicle. Will not track global active vehicle changes.
Q_INVOKABLE virtual void startStaticActiveVehicle(Vehicle* vehicle);
Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle);
/// Determines if the plan has all data needed to be saved or sent to the vehicle. Currently the only case where this
/// would return false is when it is still waiting on terrain data to determine correct altitudes.
Q_INVOKABLE bool readyForSaveSend(void) const { return _missionController.readyForSaveSend(); }
/// Sends a plan to the specified file
/// @param[in] vehicle Vehicle we are sending a plan to
......
This diff is collapsed.
......@@ -29,12 +29,21 @@ public:
~SimpleMissionItem();
const SimpleMissionItem& operator=(const SimpleMissionItem& other);
enum AltitudeMode {
AltitudeRelative,
AltitudeAMSL,
AltitudeAboveTerrain
};
Q_ENUM(AltitudeMode)
Q_PROPERTY(QString category READ category NOTIFY commandChanged)
Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged)
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 specifiesAltitude READ specifiesAltitude NOTIFY commandChanged)
Q_PROPERTY(Fact* altitude READ altitude CONSTANT) ///< Altitude as specified by altitudeMode. Not necessarily true mission item altitude
Q_PROPERTY(AltitudeMode altitudeMode READ altitudeMode WRITE setAltitudeMode NOTIFY altitudeModeChanged)
Q_PROPERTY(Fact* amslAltAboveTerrain READ amslAltAboveTerrain CONSTANT) ///< Actual AMSL altitude for item if altitudeMode == AltitudeAboveTerrain
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
/// Optional sections
......@@ -42,7 +51,6 @@ public:
Q_PROPERTY(QObject* cameraSection READ cameraSection NOTIFY cameraSectionChanged)
// These properties are used to display the editing ui
Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts CONSTANT)
Q_PROPERTY(QmlObjectListModel* comboboxFacts READ comboboxFacts CONSTANT)
Q_PROPERTY(QmlObjectListModel* textFieldFacts READ textFieldFacts CONSTANT)
Q_PROPERTY(QmlObjectListModel* nanFacts READ nanFacts CONSTANT)
......@@ -60,15 +68,20 @@ public:
MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_missionItem._commandFact.cookedValue().toInt(); }
bool friendlyEditAllowed (void) const;
bool rawEdit (void) const;
bool specifiesAltitude (void) const;
AltitudeMode altitudeMode (void) const { return _altitudeMode; }
Fact* altitude (void) { return &_altitudeFact; }
Fact* amslAltAboveTerrain (void) { return &_amslAltAboveTerrainFact; }
CameraSection* cameraSection (void) { return _cameraSection; }
SpeedSection* speedSection (void) { return _speedSection; }
QmlObjectListModel* textFieldFacts (void) { return &_textFieldFacts; }
QmlObjectListModel* nanFacts (void) { return &_nanFacts; }
QmlObjectListModel* checkboxFacts (void) { return &_checkboxFacts; }
QmlObjectListModel* comboboxFacts (void) { return &_comboboxFacts; }
void setRawEdit(bool rawEdit);
void setAltitudeMode(AltitudeMode altitudeMode);
void setCommandByIndex(int index);
......@@ -82,8 +95,6 @@ public:
bool load(QTextStream &loadStream);
bool load(const QJsonObject& json, int sequenceNumber, QString& errorString);
bool relativeAltitude(void) { return _missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT; }
MissionItem& missionItem(void) { return _missionItem; }
const MissionItem& missionItem(void) const { return _missionItem; }
......@@ -107,6 +118,7 @@ public:
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const final;
bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return coordinateHasRelativeAltitude(); }
......@@ -123,51 +135,51 @@ public slots:
signals:
void commandChanged (int command);
void frameChanged (int frame);
void friendlyEditAllowedChanged (bool friendlyEditAllowed);
void headingDegreesChanged (double heading);
void rawEditChanged (bool rawEdit);
void cameraSectionChanged (QObject* cameraSection);
void speedSectionChanged (QObject* cameraSection);
void altitudeModeChanged (void);
private slots:
void _setDirtyFromSignal (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFrameChanged (void);
void _sendFriendlyEditAllowedChanged (void);
void _syncAltitudeRelativeToHomeToFrame (const QVariant& value);
void _syncFrameToAltitudeRelativeToHome (void);
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _setDirty (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFriendlyEditAllowedChanged(void);
void _altitudeChanged (void);
void _altitudeModeChanged (void);
void _terrainAltChanged (void);
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
private:
void _connectSignals (void);
void _setupMetaData (void);
void _updateOptionalSections(void);
void _rebuildTextFieldFacts (void);
void _rebuildNaNFacts (void);
void _rebuildCheckboxFacts (void);
void _rebuildComboBoxFacts (void);
MissionItem _missionItem;
bool _rawEdit;
bool _dirty;
bool _ignoreDirtyChangeSignals;
MissionItem _missionItem;
bool _rawEdit;
bool _dirty;
bool _ignoreDirtyChangeSignals;
SpeedSection* _speedSection;
CameraSection* _cameraSection;
MissionCommandTree* _commandTree;
Fact _altitudeRelativeToHomeFact;
Fact _supportedCommandFact;
Fact _supportedCommandFact;
AltitudeMode _altitudeMode;
Fact _altitudeFact;
Fact _amslAltAboveTerrainFact;
QmlObjectListModel _textFieldFacts;
QmlObjectListModel _nanFacts;
QmlObjectListModel _checkboxFacts;
QmlObjectListModel _comboboxFacts;
static FactMetaData* _altitudeMetaData;
......@@ -185,8 +197,11 @@ private:
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
bool _syncingHeadingDegreesAndParam4; ///< true: already in a sync signal, prevents signal loop
static const char* _jsonAltitudeModeKey;
static const char* _jsonAltitudeKey;
static const char* _jsonAMSLAltAboveTerrainKey;
};
#endif
......@@ -15,43 +15,37 @@
const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_UNLIM, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_UNLIM, MAV_FRAME_GLOBAL },
{ MAV_CMD_NAV_LOITER_TURNS, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_TIME, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_TIME, MAV_FRAME_GLOBAL },
{ MAV_CMD_NAV_LAND, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_TAKEOFF, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_TAKEOFF, MAV_FRAME_GLOBAL },
{ MAV_CMD_DO_JUMP, MAV_FRAME_MISSION },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesWaypoint[] = {
{ "Altitude", 70.1234567 },
{ "Hold", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterUnlim[] = {
{ "Altitude", 70.1234567 },
{ "Radius", 30.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTurns[] = {
{ "Altitude", 70.1234567 },
{ "Radius", 30.1234567 },
{ "Turns", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTime[] = {
{ "Altitude", 70.1234567 },
{ "Radius", 30.1234567 },
{ "Hold", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLand[] = {
{ "Altitude", 70.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesTakeoff[] = {
{ "Pitch", 10.1234567 },
{ "Altitude", 70.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJump[] = {
......@@ -60,13 +54,14 @@ const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJ
};
const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpected[] = {
{ sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLand)/sizeof(SimpleMissionItemTest::_rgFactValuesLand[0]), SimpleMissionItemTest::_rgFactValuesLand, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, false },
// Text field facts count Fact Values Altitude Altitude Mode
{ sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, 70.1234567, SimpleMissionItem::AltitudeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, SimpleMissionItem::AltitudeAMSL },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, 70.1234567, SimpleMissionItem::AltitudeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, SimpleMissionItem::AltitudeAMSL },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLand)/sizeof(SimpleMissionItemTest::_rgFactValuesLand[0]), SimpleMissionItemTest::_rgFactValuesLand, 70.1234567, SimpleMissionItem::AltitudeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, SimpleMissionItem::AltitudeAMSL },
{ sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, qQNaN(), SimpleMissionItem::AltitudeRelative },
};
SimpleMissionItemTest::SimpleMissionItemTest(void)
......@@ -80,12 +75,12 @@ void SimpleMissionItemTest::init(void)
VisualMissionItemTest::init();
rgSimpleItemSignals[commandChangedIndex] = SIGNAL(commandChanged(int));
rgSimpleItemSignals[frameChangedIndex] = SIGNAL(frameChanged(int));
rgSimpleItemSignals[altitudeModeChangedIndex] = SIGNAL(altitudeModeChanged());
rgSimpleItemSignals[friendlyEditAllowedChangedIndex] = SIGNAL(friendlyEditAllowedChanged(bool));
rgSimpleItemSignals[headingDegreesChangedIndex] = SIGNAL(headingDegreesChanged(double));
rgSimpleItemSignals[rawEditChangedIndex] = SIGNAL(rawEditChanged(bool));
rgSimpleItemSignals[cameraSectionChangedIndex] = SIGNAL(rawEditChanged(bool));
rgSimpleItemSignals[speedSectionChangedIndex] = SIGNAL(rawEditChanged(bool));
rgSimpleItemSignals[cameraSectionChangedIndex] = SIGNAL(cameraSectionChanged(QObject*));
rgSimpleItemSignals[speedSectionChangedIndex] = SIGNAL(speedSectionChanged(QObject*));
rgSimpleItemSignals[coordinateHasRelativeAltitudeChangedIndex] = SIGNAL(coordinateHasRelativeAltitudeChanged(bool));
MissionItem missionItem(1, // sequence number
......@@ -164,8 +159,10 @@ void SimpleMissionItemTest::_testEditorFacts(void)
}
QCOMPARE(factCount, expected->cFactValues);
int expectedCount = expected->relativeAltCheckbox ? 1 : 0;
QCOMPARE(simpleMissionItem.checkboxFacts()->count(), expectedCount);
if (!qIsNaN(expected->altValue)) {
QCOMPARE(simpleMissionItem.altitudeMode(), expected->altMode);
QCOMPARE(simpleMissionItem.altitude()->rawValue().toDouble(), expected->altValue);
}
}
delete vehicle;
......@@ -228,18 +225,8 @@ void SimpleMissionItemTest::_testSignals(void)
QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask));
_spyVisualItem->clearAllSignals();
// Check frameChanged signalling. Calling setFrame should signal:
// frameChanged
// dirtyChanged
// friendlyEditAllowedChanged - this signal is not very smart on when it gets sent
// coordinateHasRelativeAltitudeChanged
missionItem.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
QVERIFY(_spyVisualItem->checkNoSignals());
QVERIFY(_spySimpleItem->checkNoSignals());
missionItem.setFrame(MAV_FRAME_GLOBAL);
QVERIFY(_spySimpleItem->checkOnlySignalByMask(frameChangedMask | dirtyChangedMask | friendlyEditAllowedChangedMask | coordinateHasRelativeAltitudeChangedMask));
_simpleItem->setAltitudeMode(_simpleItem->altitudeMode() == SimpleMissionItem::AltitudeRelative ? SimpleMissionItem::AltitudeAMSL : SimpleMissionItem::AltitudeRelative);
QVERIFY(_spySimpleItem->checkOnlySignalByMask(dirtyChangedMask | friendlyEditAllowedChangedMask | altitudeModeChangedMask | coordinateHasRelativeAltitudeChangedMask));
_spySimpleItem->clearAllSignals();
_spyVisualItem->clearAllSignals();
......@@ -320,3 +307,18 @@ void SimpleMissionItemTest::_testSpeedSection(void)
QCOMPARE(_spyVisualItem->checkSignalsByMask(specifiedFlightSpeedChangedMask), true);
QCOMPARE(_simpleItem->dirty(), true);
}
void SimpleMissionItemTest::_testAltitudePropogation(void)
{
// Make sure that changes to altitude propogate to param 7 of the mission item
_simpleItem->setAltitudeMode(SimpleMissionItem::AltitudeRelative);
_simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1);
QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7());
QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL_RELATIVE_ALT);
_simpleItem->setAltitudeMode(SimpleMissionItem::AltitudeAMSL);
_simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1);
QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7());
QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL);
}
......@@ -31,11 +31,12 @@ private slots:
void _testSpeedSectionDirty(void);
void _testCameraSection(void);
void _testSpeedSection(void);
void _testAltitudePropogation(void);
private:
enum {
commandChangedIndex = 0,
frameChangedIndex,
altitudeModeChangedIndex,
friendlyEditAllowedChangedIndex,
headingDegreesChangedIndex,
rawEditChangedIndex,
......@@ -47,7 +48,7 @@ private:
enum {
commandChangedMask = 1 << commandChangedIndex,
frameChangedMask = 1 << frameChangedIndex,
altitudeModeChangedMask = 1 << altitudeModeChangedIndex,
friendlyEditAllowedChangedMask = 1 << friendlyEditAllowedChangedIndex,
headingDegreesChangedMask = 1 << headingDegreesChangedIndex,
rawEditChangedMask = 1 << rawEditChangedIndex,
......@@ -70,9 +71,10 @@ private:
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
bool relativeAltCheckbox;
size_t cFactValues;
const FactValue_t* rgFactValues;
double altValue;
SimpleMissionItem::AltitudeMode altMode;
} ItemExpected_t;
SimpleMissionItem* _simpleItem;
......
......@@ -43,7 +43,7 @@ public:
Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< 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(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) ///< The altitude of terrain at the coordinate position, NaN if not known
Q_PROPERTY(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) ///< The altitude of terrain at the coordinate position, NaN if not known
Q_PROPERTY(bool coordinateHasRelativeAltitude READ coordinateHasRelativeAltitude NOTIFY coordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude
Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged) ///< This is the exit point for a waypoint line coming out of the item.
Q_PROPERTY(bool exitCoordinateHasRelativeAltitude READ exitCoordinateHasRelativeAltitude NOTIFY exitCoordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude
......@@ -130,6 +130,11 @@ public:
virtual void setSequenceNumber (int sequenceNumber) = 0;
virtual int lastSequenceNumber (void) const = 0;
/// Specifies whether the item has all the data it needs such that it can be saved. Currently the only
/// case where this returns false is if it has not determined terrain values yet.
/// @return true: Ready to save, false: Still waiting on information
virtual bool readyForSave(void) const { return true; }
/// Save the item(s) in Json format
/// @param missionItems Current set of mission items, new items should be appended to the end
virtual void save(QJsonArray& missionItems) = 0;
......
......@@ -162,7 +162,15 @@ QGCView {
_missionController.setCurrentPlanViewIndex(0, true)
}
function waitingOnDataMessage() {
_qgcView.showMessage(qsTr("Unable to Save/Upload"), qsTr("Plan is waiting on terrain data from server for correct altitude values."), StandardButton.Ok)
}
function upload() {
if (!readyForSaveSend()) {
waitingOnDataMessage()
return
}
if (_activeVehicle && _activeVehicle.armed && _activeVehicle.flightMode === _activeVehicle.missionFlightMode) {
_qgcView.showDialog(activeMissionUploadDialogComponent, qsTr("Plan Upload"), _qgcView.showDialogDefaultWidth, StandardButton.Cancel)
} else {
......@@ -178,6 +186,10 @@ QGCView {
}
function saveToSelectedFile() {
if (!readyForSaveSend()) {
waitingOnDataMessage()
return
}
fileDialog.title = qsTr("Save Plan")
fileDialog.plan = true
fileDialog.selectExisting = false
......@@ -190,6 +202,10 @@ QGCView {
}
function saveKmlToSelectedFile() {
if (!readyForSaveSend()) {
waitingOnDataMessage()
return
}
fileDialog.title = qsTr("Save KML")
fileDialog.plan = false
fileDialog.selectExisting = false
......
......@@ -17,6 +17,9 @@ Rectangle {
color: qgcPal.windowShadeDark
radius: _radius
property bool _specifiesAltitude: missionItem.specifiesAltitude
property bool _altModeIsTerrain: missionItem.altitudeMode === 2
Column {
id: valuesColumn
anchors.margins: _margin
......@@ -68,9 +71,27 @@ Rectangle {
anchors.left: parent.left
anchors.right: parent.right
flow: GridLayout.TopToBottom
rows: missionItem.textFieldFacts.count + missionItem.nanFacts.count + (missionItem.speedSection.available ? 1 : 0)
rows: missionItem.textFieldFacts.count +
missionItem.nanFacts.count +
(missionItem.speedSection.available ? 1 : 0) +
(_specifiesAltitude ? 1 : 0) +
(_altModeIsTerrain ? 1 : 0)
columns: 2
QGCComboBox {
id: altCombo
model: [ qsTr("Alt (Rel)"), qsTr("AMSL"), qsTr("Above Terrain") ]
currentIndex: missionItem.altitudeMode
Layout.fillWidth: true
onActivated: missionItem.altitudeMode = index
visible: _specifiesAltitude
}
QGCLabel {
text: qsTr("Actual AMSL Alt")
visible: _altModeIsTerrain
}
Repeater {
model: missionItem.textFieldFacts
......@@ -95,6 +116,19 @@ Rectangle {
visible: missionItem.speedSection.available
}
FactTextField {
showUnits: true
fact: missionItem.altitude
Layout.fillWidth: true
visible: _specifiesAltitude
}
FactLabel {
fact: missionItem.amslAltAboveTerrain
visible: _altModeIsTerrain
}
Repeater {
model: missionItem.textFieldFacts
......@@ -102,6 +136,7 @@ Rectangle {
showUnits: true
fact: object
Layout.fillWidth: true
enabled: !object.readOnly
}
}
......@@ -124,15 +159,6 @@ Rectangle {
}
}
Repeater {
model: missionItem.checkboxFacts
FactCheckBox {
text: object.name
fact: object
}
}
CameraSection {
checked: missionItem.cameraSection.settingsSpecified
visible: missionItem.cameraSection.available
......
......@@ -77,7 +77,7 @@ void TerrainBatchManager::_sendNextBatch(void)
QUrlQuery query;
query.addQueryItem(QStringLiteral("points"), points);
QUrl url(QStringLiteral("https://api.airmap.com/elevation/stage/srtm1/ele"));
QUrl url(QStringLiteral("https://api.airmap.com/elevation/v1/ele"));
url.setQuery(query);
QNetworkRequest request(url);
......
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