Newer
Older
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "FixedWingLandingComplexItem.h"
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include <QPolygonF>
QGC_LOGGING_CATEGORY(FixedWingLandingComplexItemLog, "FixedWingLandingComplexItemLog")
const char* FixedWingLandingComplexItem::jsonComplexItemTypeValue = "fwLandingPattern";
const char* FixedWingLandingComplexItem::_loiterToLandDistanceName = "Landing dist";
const char* FixedWingLandingComplexItem::_landingHeadingName = "Landing heading";
const char* FixedWingLandingComplexItem::_loiterAltitudeName = "Loiter altitude";
const char* FixedWingLandingComplexItem::_loiterRadiusName = "Loiter radius";
const char* FixedWingLandingComplexItem::_landingAltitudeName = "Landing altitude";
const char* FixedWingLandingComplexItem::_fallRateName = "Descent rate";
const char* FixedWingLandingComplexItem::_jsonLoiterCoordinateKey = "loiterCoordinate";
const char* FixedWingLandingComplexItem::_jsonLoiterRadiusKey = "loiterRadius";
const char* FixedWingLandingComplexItem::_jsonLoiterClockwiseKey = "loiterClockwise";
const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonLandingCoordinateKey = "landCoordinate";
const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fallRate";
QMap<QString, FactMetaData*> FixedWingLandingComplexItem::_metaDataMap;
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem(vehicle, parent)
, _sequenceNumber(0)
, _dirty(false)
, _landingCoordSet(false)
, _ignoreRecalcSignals(false)
, _landingDistanceFact (0, _loiterToLandDistanceName, FactMetaData::valueTypeDouble)
, _loiterAltitudeFact (0, _loiterAltitudeName, FactMetaData::valueTypeDouble)
, _loiterRadiusFact (0, _loiterRadiusName, FactMetaData::valueTypeDouble)
, _landingHeadingFact (0, _landingHeadingName, FactMetaData::valueTypeDouble)
, _landingAltitudeFact (0, _landingAltitudeName, FactMetaData::valueTypeDouble)
, _fallRateFact (0, _fallRateName, FactMetaData::valueTypeDouble)
, _loiterClockwise(true)
, _loiterAltitudeRelative(true)
, _landingAltitudeRelative(true)
{
_editorQml = "qrc:/qml/FWLandingPatternEditor.qml";
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), NULL /* metaDataParent */);
}
_landingDistanceFact.setMetaData (_metaDataMap[_loiterToLandDistanceName]);
_loiterAltitudeFact.setMetaData (_metaDataMap[_loiterAltitudeName]);
_loiterRadiusFact.setMetaData (_metaDataMap[_loiterRadiusName]);
_landingHeadingFact.setMetaData (_metaDataMap[_landingHeadingName]);
_landingAltitudeFact.setMetaData (_metaDataMap[_landingAltitudeName]);
_fallRateFact.setMetaData (_metaDataMap[_fallRateName]);
_landingDistanceFact.setRawValue (_landingDistanceFact.rawDefaultValue());
_loiterAltitudeFact.setRawValue (_loiterAltitudeFact.rawDefaultValue());
_loiterRadiusFact.setRawValue (_loiterRadiusFact.rawDefaultValue());
_landingHeadingFact.setRawValue (_landingHeadingFact.rawDefaultValue());
_landingAltitudeFact.setRawValue (_landingAltitudeFact.rawDefaultValue());
_fallRateFact.setRawValue (_fallRateFact.rawDefaultValue());
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact);
connect(&_landingAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact);
connect(&_landingDistanceFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange);
connect(&_landingHeadingFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange);
connect(&_loiterRadiusFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_recalcFromRadiusChange);
connect(this, &FixedWingLandingComplexItem::loiterClockwiseChanged, this, &FixedWingLandingComplexItem::_recalcFromRadiusChange);
connect(this, &FixedWingLandingComplexItem::loiterCoordinateChanged, this, &FixedWingLandingComplexItem::_recalcFromCoordinateChange);
connect(this, &FixedWingLandingComplexItem::landingCoordinateChanged, this, &FixedWingLandingComplexItem::_recalcFromCoordinateChange);
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(&_landingAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(&_landingDistanceFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(&_landingHeadingFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(&_loiterRadiusFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::loiterCoordinateChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::landingCoordinateChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::loiterClockwiseChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::loiterAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::landingAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::loiterAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged);
connect(this, &FixedWingLandingComplexItem::landingAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged);
}
int FixedWingLandingComplexItem::lastSequenceNumber(void) const
{
// land start, loiter, land
return _sequenceNumber + 2;
}
void FixedWingLandingComplexItem::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(_dirty);
}
}
void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
saveObject[JsonHelper::jsonVersionKey] = 1;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
QGeoCoordinate coordinate;
QJsonValue jsonCoordinate;
coordinate = _loiterCoordinate;
coordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
saveObject[_jsonLoiterCoordinateKey] = jsonCoordinate;
coordinate = _landingCoordinate;
coordinate.setAltitude(_landingAltitudeFact.rawValue().toDouble());
JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
saveObject[_jsonLandingCoordinateKey] = jsonCoordinate;
saveObject[_jsonLoiterRadiusKey] = _loiterRadiusFact.rawValue().toDouble();
saveObject[_jsonLoiterClockwiseKey] = _loiterClockwise;
saveObject[_jsonLoiterAltitudeRelativeKey] = _loiterAltitudeRelative;
saveObject[_jsonLandingAltitudeRelativeKey] = _landingAltitudeRelative;
}
void FixedWingLandingComplexItem::setSequenceNumber(int sequenceNumber)
{
if (_sequenceNumber != sequenceNumber) {
_sequenceNumber = sequenceNumber;
emit sequenceNumberChanged(sequenceNumber);
emit lastSequenceNumberChanged(lastSequenceNumber());
}
}
bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ _jsonLoiterCoordinateKey, QJsonValue::Array, true },
{ _jsonLoiterRadiusKey, QJsonValue::Double, true },
{ _jsonLoiterClockwiseKey, QJsonValue::Bool, true },
{ _jsonLoiterAltitudeRelativeKey, QJsonValue::Bool, true },
{ _jsonLandingCoordinateKey, QJsonValue::Array, true },
{ _jsonLandingAltitudeRelativeKey, QJsonValue::Bool, true },
};
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
setSequenceNumber(sequenceNumber);
_ignoreRecalcSignals = true;
QGeoCoordinate coordinate;
if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLoiterCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
return false;
}
_loiterCoordinate = coordinate;
_loiterAltitudeFact.setRawValue(coordinate.altitude());
if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
return false;
_landingCoordinate = coordinate;
_landingAltitudeFact.setRawValue(coordinate.altitude());
_loiterRadiusFact.setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble());
_loiterClockwise = complexObject[_jsonLoiterClockwiseKey].toBool();
_loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool();
_landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool();
_landingCoordSet = true;
_ignoreRecalcSignals = false;
_recalcFromCoordinateChange();
return true;
}
double FixedWingLandingComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
{
return qMax(_loiterCoordinate.distanceTo(other),_landingCoordinate.distanceTo(other));
}
bool FixedWingLandingComplexItem::specifiesCoordinate(void) const
{
return true;
}
void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
int seqNum = _sequenceNumber;
// IMPORTANT NOTE: Any changes here must also be taken into account in scanForItem
MissionItem* item = new MissionItem(seqNum++, // sequence number
MAV_CMD_DO_LAND_START, // MAV_CMD
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 1-7
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
float loiterRadius = _loiterRadiusFact.rawValue().toDouble() * (_loiterClockwise ? 1.0 : -1.0);
item = new MissionItem(seqNum++,
MAV_CMD_NAV_LOITER_TO_ALT,
_loiterAltitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
1.0, // Heading required = true
loiterRadius, // Loiter radius
0.0, // param 3 - unused
_loiterCoordinate.latitude(),
_loiterCoordinate.longitude(),
_loiterAltitudeFact.rawValue().toDouble(),
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
item = new MissionItem(seqNum++,
MAV_CMD_NAV_LAND,
_landingAltitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
_landingCoordinate.latitude(),
_landingCoordinate.longitude(),
_landingAltitudeFact.rawValue().toDouble(),
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
qCDebug(FixedWingLandingComplexItemLog) << "FixedWingLandingComplexItem::scanForItem count" << visualItems->count();
if (visualItems->count() < 4) {
return false;
}
int lastItem = visualItems->count() - 1;
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(lastItem--);
if (!item) {
return false;
}
MissionItem& missionItemLand = item->missionItem();
if (missionItemLand.command() != MAV_CMD_NAV_LAND ||
!(missionItemLand.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItemLand.frame() == MAV_FRAME_GLOBAL) ||
missionItemLand.param1() != 0 || missionItemLand.param2() != 0 || missionItemLand.param3() != 0 || missionItemLand.param4() == 1.0) {
return false;
}
item = visualItems->value<SimpleMissionItem*>(lastItem--);
if (!item) {
return false;
}
MissionItem& missionItemLoiter = item->missionItem();
if (missionItemLoiter.command() != MAV_CMD_NAV_LOITER_TO_ALT ||
!(missionItemLoiter.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItemLoiter.frame() == MAV_FRAME_GLOBAL) ||
missionItemLoiter.param1() != 1.0 || missionItemLoiter.param3() != 0 || missionItemLoiter.param4() != 1.0) {
return false;
}
item = visualItems->value<SimpleMissionItem*>(lastItem--);
if (!item) {
return false;
}
MissionItem& missionItemDoLandStart = item->missionItem();
if (missionItemDoLandStart.command() != MAV_CMD_DO_LAND_START ||
missionItemDoLandStart.param1() != 0 || missionItemDoLandStart.param2() != 0 || missionItemDoLandStart.param3() != 0 || missionItemDoLandStart.param4() != 0|| missionItemDoLandStart.param5() != 0|| missionItemDoLandStart.param6() != 0|| missionItemDoLandStart.param6() != 0) {
return false;
}
// We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission
FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, visualItems);
complexItem->_ignoreRecalcSignals = true;
complexItem->_loiterAltitudeRelative = missionItemLoiter.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT;
complexItem->_loiterRadiusFact.setRawValue(qAbs(missionItemLoiter.param2()));
complexItem->_loiterClockwise = missionItemLoiter.param2() > 0;
complexItem->_loiterCoordinate.setLatitude(missionItemLoiter.param5());
complexItem->_loiterCoordinate.setLongitude(missionItemLoiter.param6());
complexItem->_loiterAltitudeFact.setRawValue(missionItemLoiter.param7());
complexItem->_landingAltitudeRelative = missionItemLand.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT;
complexItem->_landingCoordinate.setLatitude(missionItemLand.param5());
complexItem->_landingCoordinate.setLongitude(missionItemLand.param6());
complexItem->_landingAltitudeFact.setRawValue(missionItemLand.param7());
complexItem->_landingCoordSet = true;
complexItem->_ignoreRecalcSignals = false;
complexItem->_recalcFromCoordinateChange();
complexItem->setDirty(false);
lastItem = visualItems->count() - 1;
visualItems->removeAt(lastItem--)->deleteLater();
visualItems->removeAt(lastItem--)->deleteLater();
visualItems->removeAt(lastItem--)->deleteLater();
visualItems->append(complexItem);
return true;
}
double FixedWingLandingComplexItem::complexDistance(void) const
{
return _loiterCoordinate.distanceTo(_landingCoordinate);
void FixedWingLandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
if (coordinate != _landingCoordinate) {
_landingCoordinate = coordinate;
if (_landingCoordSet) {
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
} else {
_ignoreRecalcSignals = true;
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
_ignoreRecalcSignals = false;
_landingCoordSet = true;
_recalcFromHeadingAndDistanceChange();
emit landingCoordSetChanged(true);
}
}
}
void FixedWingLandingComplexItem::setLoiterCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _loiterCoordinate) {
_loiterCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit loiterCoordinateChanged(coordinate);
}
}
double FixedWingLandingComplexItem::_mathematicAngleToHeading(double angle)
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
double heading = (angle - 90) * -1;
if (heading < 0) {
heading += 360;
}
return heading;
}
double FixedWingLandingComplexItem::_headingToMathematicAngle(double heading)
{
return heading - 90 * -1;
}
void FixedWingLandingComplexItem::_recalcFromRadiusChange(void)
{
// Fixed:
// land
// loiter tangent
// distance
// radius
// heading
// Adjusted:
// loiter
if (!_ignoreRecalcSignals) {
// These are our known values
double radius = _loiterRadiusFact.rawValue().toDouble();
double landToTangentDistance = _landingDistanceFact.rawValue().toDouble();
double heading = _landingHeadingFact.rawValue().toDouble();
double landToLoiterDistance = _landingCoordinate.distanceTo(_loiterCoordinate);
if (landToLoiterDistance < radius) {
// Degnenerate case: Move tangent to loiter point
_loiterTangentCoordinate = _loiterCoordinate;
double heading = _landingCoordinate.azimuthTo(_loiterTangentCoordinate);
_ignoreRecalcSignals = true;
_landingHeadingFact.setRawValue(heading);
emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
_ignoreRecalcSignals = false;
} else {
double landToLoiterDistance = qSqrt(qPow(radius, 2) + qPow(landToTangentDistance, 2));
double angleLoiterToTangent = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (_loiterClockwise ? -1 : 1);
_loiterCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToLoiterDistance, heading + 180 + angleLoiterToTangent);
_loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
_ignoreRecalcSignals = true;
emit loiterCoordinateChanged(_loiterCoordinate);
emit coordinateChanged(_loiterCoordinate);
_ignoreRecalcSignals = false;
}
void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
{
// Fixed:
// land
// heading
// distance
// radius
// Adjusted:
// loiter
// loiter tangent
if (!_ignoreRecalcSignals && _landingCoordSet) {
// These are our known values
double radius = _loiterRadiusFact.rawValue().toDouble();
double landToTangentDistance = _landingDistanceFact.rawValue().toDouble();
double heading = _landingHeadingFact.rawValue().toDouble();
// Calculate loiter tangent coordinate
_loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, heading + 180);
// Calculate the distance and angle to the loiter coordinate
QGeoCoordinate tangent = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, 0);
QGeoCoordinate loiter = tangent.atDistanceAndAzimuth(radius, 90);
double loiterDistance = _landingCoordinate.distanceTo(loiter);
double loiterAzimuth = _landingCoordinate.azimuthTo(loiter) * (_loiterClockwise ? -1 : 1);
// Use those values to get the new loiter point which takes heading into acount
_loiterCoordinate = _landingCoordinate.atDistanceAndAzimuth(loiterDistance, heading + 180 + loiterAzimuth);
_loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
emit loiterCoordinateChanged(_loiterCoordinate);
emit coordinateChanged(_loiterCoordinate);
}
QPointF FixedWingLandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
QPointF rotated;
double radians = (M_PI / 180.0) * angle;
rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());
return rotated;
}
void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
// Fixed:
// land
// loiter
// radius
// Adjusted:
// loiter tangent
// heading
// distance
if (!_ignoreRecalcSignals && _landingCoordSet) {
// These are our known values
double radius = _loiterRadiusFact.rawValue().toDouble();
double landToLoiterDistance = _landingCoordinate.distanceTo(_loiterCoordinate);
double landToLoiterHeading = _landingCoordinate.azimuthTo(_loiterCoordinate);
double landToTangentDistance;
if (landToLoiterDistance < radius) {
// Degenerate case, set tangent to loiter coordinate
_loiterTangentCoordinate = _loiterCoordinate;
landToTangentDistance = _landingCoordinate.distanceTo(_loiterTangentCoordinate);
} else {
double loiterToTangentAngle = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (_loiterClockwise ? 1 : -1);
landToTangentDistance = qSqrt(qPow(landToLoiterDistance, 2) - qPow(radius, 2));
_loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, landToLoiterHeading + loiterToTangentAngle);
}
double heading = _loiterTangentCoordinate.azimuthTo(_landingCoordinate);
_ignoreRecalcSignals = true;
_landingHeadingFact.setRawValue(heading);
_landingDistanceFact.setRawValue(landToTangentDistance);
emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
void FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact(void)
{
_loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
emit loiterCoordinateChanged(_loiterCoordinate);
emit coordinateChanged(_loiterCoordinate);
}
void FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact(void)
{
_landingCoordinate.setAltitude(_landingAltitudeFact.rawValue().toDouble());
emit landingCoordinateChanged(_landingCoordinate);
void FixedWingLandingComplexItem::_setDirty(void)
{
setDirty(true);
}
void FixedWingLandingComplexItem::applyNewAltitude(double newAltitude)
{
_loiterAltitudeFact.setRawValue(newAltitude);
}