Unverified Commit 48ffa39e authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #9071 from DonLakeFlyer/LandingPattern

Landing Pattern: Loiter to alt optional support
parents a671b146 138bdfa9
......@@ -472,6 +472,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/CameraSectionTest.h \
src/MissionManager/CorridorScanComplexItemTest.h \
src/MissionManager/FWLandingPatternTest.h \
src/MissionManager/LandingComplexItemTest.h \
src/MissionManager/MissionCommandTreeEditorTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
......@@ -519,6 +520,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/CameraSectionTest.cc \
src/MissionManager/CorridorScanComplexItemTest.cc \
src/MissionManager/FWLandingPatternTest.cc \
src/MissionManager/LandingComplexItemTest.cc \
src/MissionManager/MissionCommandTreeEditorTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
......
......@@ -17,6 +17,8 @@
#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2 //-- Send capture status every 5 seconds
class PlanMasterController;
class CameraSectionTest;
class CameraSection : public Section
{
......@@ -131,4 +133,6 @@ private:
static const char* _cameraPhotoIntervalDistanceName;
static const char* _cameraPhotoIntervalTimeName;
static const char* _cameraModeName;
friend CameraSectionTest;
};
......@@ -12,6 +12,8 @@
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
#include <functional>
CameraSectionTest::CameraSectionTest(void)
: _spyCamera (nullptr)
, _spySection (nullptr)
......@@ -44,11 +46,24 @@ void CameraSectionTest::init(void)
_validGimbalItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0, MAV_CMD_DO_MOUNT_CONTROL, MAV_FRAME_MISSION, 10.1234, 0, 20.1234, 0, 0, 0, MAV_MOUNT_MODE_MAVLINK_TARGETING, true, false),
MissionItem(0,
MAV_CMD_DO_MOUNT_CONTROL,
MAV_FRAME_MISSION,
10.1234, 0, 20.1234, // pitch, roll, yaw
0, 0, 0, // alt, lat, lon (all 0 since unused)
MAV_MOUNT_MODE_MAVLINK_TARGETING, // control gimbal with pitch, roll, yaw settings
true, false),
this);
_validTimeItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false),
MissionItem(0,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // Reserved, must be 0
48, // time interval
0, // 0 = capture forever
NAN, NAN, NAN, NAN, // Reserved
true, false),
this);
_validDistanceItem = new SimpleMissionItem(_masterController,
false, // flyView
......@@ -615,12 +630,12 @@ void CameraSectionTest::_testScanForGimbalSection(void)
Mission Param #5 WIP: latitude in degrees * 1E7, set if appropriate mount mode.
Mission Param #6 WIP: longitude in degrees * 1E7, set if appropriate mount mode.
Mission Param #7 MAV_MOUNT_MODE enum value
*/
*/
// Gimbal command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validGimbalItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam2(10); // roll is not supported
invalidSimpleItem.missionItem().setParam2(10); // roll is not supported, should be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......@@ -629,7 +644,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
visualItems.clear();
invalidSimpleItem.missionItem() = _validGimbalItem->missionItem();
invalidSimpleItem.missionItem().setParam4(10); // alt is not supported
invalidSimpleItem.missionItem().setParam4(10); // alt is not supported, should be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......@@ -638,7 +653,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
visualItems.clear();
invalidSimpleItem.missionItem() = _validGimbalItem->missionItem();
invalidSimpleItem.missionItem().setParam5(10); // lat is not supported
invalidSimpleItem.missionItem().setParam5(10); // lat is not supported, should be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......@@ -647,7 +662,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
visualItems.clear();
invalidSimpleItem.missionItem() = _validGimbalItem->missionItem();
invalidSimpleItem.missionItem().setParam6(10); // lon is not supported
invalidSimpleItem.missionItem().setParam6(10); // lon is not supported, should be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......@@ -709,14 +724,27 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
*/
// Mode command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validCameraPhotoModeItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->specifyCameraMode(), false);
QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear();
std::function<void(MissionItem&, double)> rgSetParamFns[] = {
&MissionItem::setParam1,
&MissionItem::setParam2,
&MissionItem::setParam3,
&MissionItem::setParam4,
&MissionItem::setParam5,
&MissionItem::setParam6,
&MissionItem::setParam7
};
for (int fnIndex=2; fnIndex<7; fnIndex++) {
rgSetParamFns[fnIndex](invalidSimpleItem.missionItem(), 0); // should be NaN
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->specifyCameraMode(), false);
QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear();
}
}
void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
......@@ -1135,3 +1163,25 @@ SimpleMissionItem* CameraSectionTest::createValidStopTimeItem(PlanMasterControll
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), true, false),
parent);
}
SimpleMissionItem* CameraSectionTest::createInvalidStopVideoItem(PlanMasterController* masterController, QObject* parent)
{
SimpleMissionItem* invalidSimpleItem = createValidStopVideoItem(masterController, parent);
invalidSimpleItem->missionItem().setParam1(10); // must be 0 to be valid for scan
return invalidSimpleItem;
}
SimpleMissionItem* CameraSectionTest::createInvalidStopDistanceItem(PlanMasterController* masterController, QObject* parent)
{
SimpleMissionItem* invalidSimpleItem = createValidStopDistanceItem(masterController, parent);
invalidSimpleItem->missionItem().setParam2(-1); // Should be 0
return invalidSimpleItem;
}
SimpleMissionItem* CameraSectionTest::createInvalidStopTimeItem(PlanMasterController* masterController, QObject* parent)
{
SimpleMissionItem* invalidSimpleItem = createValidStopTimeItem(masterController, parent);
invalidSimpleItem->missionItem().setParam1(1); // Should be 0
return invalidSimpleItem;
}
......@@ -24,9 +24,12 @@ public:
void init(void) override;
void cleanup(void) override;
static SimpleMissionItem* createValidStopVideoItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopDistanceItem(PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopTimeItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopVideoItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopDistanceItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopTimeItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createInvalidStopVideoItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createInvalidStopDistanceItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createInvalidStopTimeItem (PlanMasterController* masterController, QObject* parent);
private slots:
void _testDirty (void);
......
......@@ -5,75 +5,87 @@
[
{
"name": "LandingDistance",
"shortDesc": "Distance between landing and loiter points.",
"shortDesc": "Distance between approach and land points.",
"type": "double",
"units": "m",
"min": 10,
"decimalPlaces": 1,
"default": 300.0
"default": 300.0
},
{
"name": "LandingHeading",
"shortDesc": "Heading from loiter point to land point.",
"shortDesc": "Heading from approach to land point.",
"type": "double",
"units": "deg",
"min": 0.0,
"max": 360.0,
"decimalPlaces": 0,
"default": 270.0
"default": 270.0
},
{
"name": "LoiterAltitude",
"shortDesc": "Aircraft will proceed to the loiter point and loiter downwards until it reaches this approach altitude. Once altitude is reached the aircraft will proceed to land.",
"name": "FinalApproachAltitude",
"shortDesc": "Altitude to begin landing approach from.",
"type": "double",
"units": "m",
"decimalPlaces": 1,
"default": 40.0
"default": 40.0
},
{
"name": "LoiterRadius",
"shortDesc": "Loiter radius.",
"shortDesc": "Loiter radius.",
"type": "double",
"decimalPlaces": 1,
"min": 1,
"units": "m",
"default": 75.0
"default": 75.0
},
{
"name": "LoiterClockwise",
"shortDesc": "Loiter clockwise around the final approach point.",
"type": "bool",
"default": true
},
{
"name": "LandingAltitude",
"shortDesc": "Altitude for landing point.",
"shortDesc": "Altitude for landing point.",
"type": "double",
"units": "m",
"decimalPlaces": 1,
"default": 0.0
"default": 0.0
},
{
"name": "GlideSlope",
"shortDesc": "The glide slope between the loiter and landing point.",
"shortDesc": "The glide slope between the loiter and landing point.",
"type": "double",
"units": "deg",
"min": 0.1,
"max": 90,
"decimalPlaces": 1,
"default": 6.0
"default": 6.0
},
{
"name": "ValueSetIsDistance",
"shortDesc": "Value controller approach point is distance",
"type": "bool",
"default": false
},
{
"name": "ValueSetIsDistance",
"shortDesc": "Value controller loiter point is distance",
"type": "bool",
"default": false
"name": "UseLoiterToAlt",
"shortDesc": "Use a loiter to altitude item for final appoach. Otherwise use a regular waypoint.",
"type": "bool",
"default": true
},
{
"name": "StopTakingPhotos",
"shortDesc": "Stop taking photos",
"type": "bool",
"default": true
"name": "StopTakingPhotos",
"shortDesc": "Stop taking photos",
"type": "bool",
"default": true
},
{
"name": "StopTakingVideo",
"shortDesc": "Stop taking video",
"type": "bool",
"default": true
"name": "StopTakingVideo",
"shortDesc": "Stop taking video",
"type": "bool",
"default": true
}
]
}
......@@ -22,18 +22,15 @@ void FWLandingPatternTest::init(void)
{
VisualMissionItemTest::init();
rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_fwItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */, this);
_multiSpy = new MultiSignalSpy();
QCOMPARE(_multiSpy->init(_fwItem, rgSignals, cSignals), true);
_createSpy(_fwItem, &_viSpy);
// Start in a clean state
QVERIFY(!_fwItem->dirty());
_fwItem->setLandingCoordinate(QGeoCoordinate(47, -122));
_fwItem->setDirty(false);
QVERIFY(!_fwItem->dirty());
_multiSpy->clearAllSignals();
_viSpy->clearAllSignals();
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
......@@ -43,7 +40,7 @@ void FWLandingPatternTest::init(void)
void FWLandingPatternTest::cleanup(void)
{
delete _fwItem;
delete _multiSpy;
delete _viSpy;
delete _validStopVideoItem;
delete _validStopDistanceItem;
delete _validStopTimeItem;
......@@ -57,142 +54,35 @@ void FWLandingPatternTest::_testDefaults(void)
QCOMPARE(_fwItem->stopTakingVideo()->rawValue().toBool(), true);
}
void FWLandingPatternTest::_testItemCount(void)
{
QList<MissionItem*> items;
_fwItem->stopTakingPhotos()->setRawValue(true);
_fwItem->stopTakingVideo()->setRawValue(true);
_fwItem->appendMissionItems(items, this);
QCOMPARE(items.count(), 3 + CameraSection::stopTakingPhotosCommandCount() + CameraSection::stopTakingVideoCommandCount());
QCOMPARE(items.count() - 1, _fwItem->lastSequenceNumber());
items.clear();
_fwItem->stopTakingPhotos()->setRawValue(false);
_fwItem->stopTakingVideo()->setRawValue(false);
_fwItem->appendMissionItems(items, this);
QCOMPARE(items.count(), 3);
QCOMPARE(items.count() - 1, _fwItem->lastSequenceNumber());
items.clear();
}
void FWLandingPatternTest::_testAppendSectionItems(void)
{
QList<MissionItem*> rgMissionItems;
// Create the set of appended mission items
_fwItem->stopTakingPhotos()->setRawValue(true);
_fwItem->stopTakingVideo()->setRawValue(true);
_fwItem->appendMissionItems(rgMissionItems, this);
// Convert to visual items
QmlObjectListModel* simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, simpleItems);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
// Scan the items back in to verify the same values come back
// Note that the compares does the best it can with doubles going to floats and back causing inaccuracies beyond a fuzzy compare.
QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _masterController));
QCOMPARE(simpleItems->count(), 1);
_validateItem(simpleItems->value<FixedWingLandingComplexItem*>(0));
// Reset
simpleItems->deleteLater();
rgMissionItems.clear();
// Check for no stop camera actions
_fwItem->stopTakingPhotos()->setRawValue(false);
_fwItem->stopTakingVideo()->setRawValue(false);
_fwItem->appendMissionItems(rgMissionItems, this);
simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, simpleItems);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _masterController));
QCOMPARE(simpleItems->count(), 1);
_validateItem(simpleItems->value<FixedWingLandingComplexItem*>(0));
// Reset
simpleItems->deleteLater();
rgMissionItems.clear();
}
void FWLandingPatternTest::_testDirty(void)
{
_fwItem->setDirty(true);
QVERIFY(_fwItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_viSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_viSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_fwItem->setDirty(false);
_multiSpy->clearAllSignals();
_viSpy->clearAllSignals();
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _fwItem->loiterAltitude()
<< _fwItem->landingHeading()
<< _fwItem->loiterRadius()
<< _fwItem->landingAltitude()
<< _fwItem->landingDistance()
<< _fwItem->glideSlope()
<< _fwItem->stopTakingPhotos()
<< _fwItem->stopTakingVideo()
rgFacts << _fwItem->glideSlope()
<< _fwItem->valueSetIsDistance();
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_fwItem->dirty());
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_fwItem->setDirty(false);
_multiSpy->clearAllSignals();
}
rgFacts.clear();
// These bool properties should set dirty when changed
QList<const char*> rgBoolNames;
rgBoolNames << "loiterClockwise"
<< "altitudesAreRelative";
const QMetaObject* metaObject = _fwItem->metaObject();
for(const char* boolName: rgBoolNames) {
qDebug() << boolName;
QVERIFY(!_fwItem->dirty());
QMetaProperty boolProp = metaObject->property(metaObject->indexOfProperty(boolName));
QVERIFY(boolProp.write(_fwItem, !boolProp.read(_fwItem).toBool()));
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
changeFactValue(fact);
QVERIFY(_viSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_viSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_fwItem->setDirty(false);
_multiSpy->clearAllSignals();
_viSpy->clearAllSignals();
}
rgFacts.clear();
// These coordinates should set dirty when changed
QVERIFY(!_fwItem->dirty());
_fwItem->setLoiterCoordinate(_fwItem->loiterCoordinate().atDistanceAndAzimuth(1, 0));
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_fwItem->setDirty(false);
_multiSpy->clearAllSignals();
QVERIFY(!_fwItem->dirty());
_fwItem->setLoiterCoordinate(_fwItem->landingCoordinate().atDistanceAndAzimuth(1, 0));
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_fwItem->setDirty(false);
_multiSpy->clearAllSignals();
}
void FWLandingPatternTest::_testSaveLoad(void)
{
QJsonArray items;
QJsonArray items;
_fwItem->save(items);
QString errorString;
......@@ -211,20 +101,6 @@ void FWLandingPatternTest::_validateItem(FixedWingLandingComplexItem* newItem)
{
QVERIFY(newItem);
QVERIFY(fuzzyCompareLatLon(newItem->loiterCoordinate(), _fwItem->loiterCoordinate()));
QVERIFY(fuzzyCompareLatLon(newItem->loiterTangentCoordinate(), _fwItem->loiterTangentCoordinate()));
QVERIFY(fuzzyCompareLatLon(newItem->landingCoordinate(), _fwItem->landingCoordinate()));
QCOMPARE(newItem->stopTakingPhotos()->rawValue().toBool(), _fwItem->stopTakingPhotos()->rawValue().toBool());
QCOMPARE(newItem->stopTakingVideo()->rawValue().toBool(), _fwItem->stopTakingVideo()->rawValue().toBool());
QCOMPARE(newItem->loiterAltitude()->rawValue().toInt(), _fwItem->loiterAltitude()->rawValue().toInt());
QCOMPARE(newItem->loiterRadius()->rawValue().toInt(), _fwItem->loiterRadius()->rawValue().toInt());
QCOMPARE(newItem->landingAltitude()->rawValue().toInt(), _fwItem->landingAltitude()->rawValue().toInt());
QCOMPARE(newItem->landingHeading()->rawValue().toInt(), _fwItem->landingHeading()->rawValue().toInt());
QCOMPARE(newItem->landingDistance()->rawValue().toInt(), _fwItem->landingDistance()->rawValue().toInt());
QCOMPARE(newItem->glideSlope()->rawValue().toInt(), _fwItem->glideSlope()->rawValue().toInt());
QCOMPARE(newItem->valueSetIsDistance()->rawValue().toBool(), _fwItem->valueSetIsDistance()->rawValue().toBool());
QCOMPARE(newItem->_loiterClockwise, _fwItem->_loiterClockwise);
QCOMPARE(newItem->_altitudesAreRelative, _fwItem->_altitudesAreRelative);
QCOMPARE(newItem->_landingCoordSet, _fwItem->_landingCoordSet);
}
......@@ -25,30 +25,16 @@ public:
void cleanup(void) override;
private slots:
void _testDirty (void);
void _testItemCount (void);
void _testDefaults (void);
void _testAppendSectionItems (void);
void _testSaveLoad (void);
void _testDirty (void);
void _testDefaults (void);
void _testSaveLoad (void);
private:
void _validateItem(FixedWingLandingComplexItem* newItem);
enum {
dirtyChangedIndex = 0,
maxSignalIndex,
};
enum {
dirtyChangedMask = 1 << dirtyChangedIndex,
};
static const size_t cSignals = maxSignalIndex;
const char* rgSignals[cSignals];
FixedWingLandingComplexItem* _fwItem = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
SimpleMissionItem* _validStopVideoItem = nullptr;
SimpleMissionItem* _validStopDistanceItem = nullptr;
SimpleMissionItem* _validStopTimeItem = nullptr;
FixedWingLandingComplexItem* _fwItem = nullptr;
MultiSignalSpy* _viSpy = nullptr;
SimpleMissionItem* _validStopVideoItem = nullptr;
SimpleMissionItem* _validStopDistanceItem = nullptr;
SimpleMissionItem* _validStopTimeItem = nullptr;
};
......@@ -32,114 +32,63 @@ public:
Q_INVOKABLE void moveLandingPosition(const QGeoCoordinate& coordinate); // Maintains the current landing distance and heading
Fact* loiterAltitude (void) final { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) final { return &_loiterRadiusFact; }
Fact* landingAltitude (void) final { return &_landingAltitudeFact; }
Fact* landingDistance (void) final { return &_landingDistanceFact; }
Fact* landingHeading (void) final { return &_landingHeadingFact; }
Fact* stopTakingPhotos (void) final { return &_stopTakingPhotosFact; }
Fact* stopTakingVideo (void) final { return &_stopTakingVideoFact; }
Fact* glideSlope (void) { return &_glideSlopeFact; }
Fact* valueSetIsDistance (void) { return &_valueSetIsDistanceFact; }
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
static MissionItem* createDoLandStartItem (int seqNum, QObject* parent);
static MissionItem* createLoiterToAltItem (int seqNum, bool altRel, double loiterRaidus, double lat, double lon, double alt, QObject* parent);
static MissionItem* createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent);
// Overrides from ComplexMissionItem
QString patternName (void) const final { return name; }
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
QString mapVisualQML (void) const final { return QStringLiteral("FWLandingPatternMapVisual.qml"); }
// 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;
bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return "Landing Pattern"; }
QString commandName (void) const final { return "Landing Pattern"; }
QString abbreviation (void) const final { return "L"; }
QGeoCoordinate coordinate (void) const final { return _loiterCoordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _landingCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
double additionalTimeDelay (void) const final { return 0; }
ReadyForSaveState readyForSaveState (void) const final;
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final { setLoiterCoordinate(coordinate); }
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonArray& missionItems) final;
double amslEntryAlt (void) const final;
double amslExitAlt (void) const final;
double minAMSLAltitude (void) const final { return amslExitAlt(); }
double maxAMSLAltitude (void) const final { return amslEntryAlt(); }
static const QString name;
static const char* jsonComplexItemTypeValue;
static const char* settingsGroup;
static const char* loiterToLandDistanceName;
static const char* loiterAltitudeName;
static const char* loiterRadiusName;
static const char* landingHeadingName;
static const char* landingAltitudeName;
static const char* glideSlopeName;
static const char* stopTakingPhotosName;
static const char* stopTakingVideoName;
static const char* valueSetIsDistanceName;
signals:
void valueSetIsDistanceChanged (bool valueSetIsDistance);
private slots:
void _updateLoiterCoodinateAltitudeFromFact (void);
void _updateLandingCoodinateAltitudeFromFact (void);
double _mathematicAngleToHeading (double angle);
double _headingToMathematicAngle (double heading);
void _setDirty (void);
void _glideSlopeChanged (void);
void _signalLastSequenceNumberChanged (void);
void _glideSlopeChanged(void);
private:
void _calcGlideSlope(void) final;
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView, QObject* parent) { return new FixedWingLandingComplexItem(masterController, flyView, parent); }
static bool _isValidLandItem(const MissionItem& missionItem);
// Overrides from LandingComplexItem
const Fact* _finalApproachAltitude (void) const final { return &_finalApproachAltitudeFact; }
const Fact* _loiterRadius (void) const final { return &_loiterRadiusFact; }
const Fact* _loiterClockwise (void) const final { return &_loiterClockwiseFact; }
const Fact* _landingAltitude (void) const final { return &_landingAltitudeFact; }
const Fact* _landingDistance (void) const final { return &_landingDistanceFact; }
const Fact* _landingHeading (void) const final { return &_landingHeadingFact; }
const Fact* _useLoiterToAlt (void) const final { return &_useLoiterToAltFact; }
const Fact* _stopTakingPhotos (void) const final { return &_stopTakingPhotosFact; }
const Fact* _stopTakingVideo (void) const final { return &_stopTakingVideoFact; }
void _calcGlideSlope (void) final;
MissionItem* _createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent) final;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _landingDistanceFact;
Fact _loiterAltitudeFact;
Fact _finalApproachAltitudeFact;
Fact _loiterRadiusFact;
Fact _loiterClockwiseFact;
Fact _landingHeadingFact;
Fact _landingAltitudeFact;
Fact _glideSlopeFact;
Fact _useLoiterToAltFact;
Fact _stopTakingPhotosFact;
Fact _stopTakingVideoFact;
Fact _valueSetIsDistanceFact;
static const char* _jsonLoiterCoordinateKey;
static const char* _jsonLoiterRadiusKey;
static const char* _jsonLoiterClockwiseKey;
static const char* _jsonLandingCoordinateKey;
static const char* _jsonValueSetIsDistanceKey;
static const char* _jsonAltitudesAreRelativeKey;
static const char* _jsonStopTakingPhotosKey;
static const char* _jsonStopTakingVideoKey;
// Only in older file formats
static const char* _jsonLandingAltitudeRelativeKey;
static const char* _jsonLoiterAltitudeRelativeKey;
static const char* _jsonFallRateKey;
friend FWLandingPatternTest;
};
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2020 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.
*
****************************************************************************/
#pragma once
#include "VisualMissionItemTest.h"
#include "LandingComplexItem.h"
#include "MultiSignalSpy.h"
#include "PlanMasterController.h"
class LandingComplexItemTest : public VisualMissionItemTest
{
Q_OBJECT
public:
LandingComplexItemTest(void);
void cleanup(void) override;
void init (void) override;
private slots:
void _testDirty (void);
void _testItemCount (void);
void _testAppendSectionItems (void);
void _testScanForItems (void);
void _testSaveLoad (void);
private:
void _validateItem(LandingComplexItem* actualItem, LandingComplexItem* expectedItem);
enum {
finalApproachCoordinateChangedIndex = 0,
loiterTangentCoordinateChangedIndex,
landingCoordinateChangedIndex,
landingCoordSetChangedIndex,
loiterClockwiseChangedIndex,
useLoiterToAltChangedIndex,
altitudesAreRelativeChangedIndex,
_updateFlightPathSegmentsSignalIndex,
maxSignalIndex,
};
enum {
finalApproachCoordinateChangedMask = 1 << finalApproachCoordinateChangedIndex,
loiterTangentCoordinateChangedMask = 1 << loiterTangentCoordinateChangedIndex,
landingCoordinateChangedMask = 1 << landingCoordinateChangedIndex,
landingCoordSetChangedMask = 1 << landingCoordSetChangedIndex,
loiterClockwiseChangedMask = 1 << loiterClockwiseChangedIndex,
useLoiterToAltChangedMask = 1 << useLoiterToAltChangedIndex,
altitudesAreRelativeChangedMask = 1 << altitudesAreRelativeChangedIndex,
_updateFlightPathSegmentsSignalMask = 1 << _updateFlightPathSegmentsSignalIndex,
};
static const size_t cSignals = maxSignalIndex;
const char* rgSignals[cSignals];
LandingComplexItem* _item = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
MultiSignalSpy* _viMultiSpy = nullptr;
SimpleMissionItem* _validStopVideoItem = nullptr;
SimpleMissionItem* _validStopDistanceItem = nullptr;
SimpleMissionItem* _validStopTimeItem = nullptr;
};
// Simple class used to test LandingComplexItem base class
class SimpleLandingComplexItem : public LandingComplexItem
{
Q_OBJECT
public:
SimpleLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
// Overrides from ComplexMissionItem
QString patternName (void) const final { return QString(); }
bool load (const QJsonObject& /*complexObject*/, int /*sequenceNumber*/, QString& /*errorString*/) final { return false; };
QString mapVisualQML(void) const final { return QStringLiteral("FWLandingPatternMapVisual.qml"); }
// Overrides from VisualMissionItem
void save (QJsonArray& /*missionItems*/) { };
static const QString name;
static const char* jsonComplexItemTypeValue;
static const char* settingsGroup;
private:
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView, QObject* parent) { return new SimpleLandingComplexItem(masterController, flyView, parent); }
static bool _isValidLandItem(const MissionItem& missionItem);
// Overrides from LandingComplexItem
const Fact* _finalApproachAltitude (void) const final { return &_finalApproachAltitudeFact; }
const Fact* _loiterRadius (void) const final { return &_loiterRadiusFact; }
const Fact* _loiterClockwise (void) const final { return &_loiterClockwiseFact; }
const Fact* _landingAltitude (void) const final { return &_landingAltitudeFact; }
const Fact* _landingDistance (void) const final { return &_landingDistanceFact; }
const Fact* _landingHeading (void) const final { return &_landingHeadingFact; }
const Fact* _useLoiterToAlt (void) const final { return &_useLoiterToAltFact; }
const Fact* _stopTakingPhotos (void) const final { return &_stopTakingPhotosFact; }
const Fact* _stopTakingVideo (void) const final { return &_stopTakingVideoFact; }
void _calcGlideSlope (void) final { };
MissionItem* _createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent) final;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _landingDistanceFact;
Fact _finalApproachAltitudeFact;
Fact _loiterRadiusFact;
Fact _loiterClockwiseFact;
Fact _landingHeadingFact;
Fact _landingAltitudeFact;
Fact _useLoiterToAltFact;
Fact _stopTakingPhotosFact;
Fact _stopTakingVideoFact;
friend class LandingComplexItemTest;
};
......@@ -2153,8 +2153,10 @@ void MissionController::setDirty(bool dirty)
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, PlanMasterController* masterController)
{
// First we look for a Fixed Wing Landing Pattern which is at the end
FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, masterController);
// First we look for a Landing Patterns which are at the end
if (!FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, masterController)) {
VTOLLandingComplexItem::scanForItem(visualItems, _flyView, masterController);
}
int scanIndex = 0;
while (scanIndex < visualItems->count()) {
......
......@@ -26,98 +26,51 @@ class VTOLLandingComplexItem : public LandingComplexItem
public:
VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
Fact* loiterAltitude (void) final { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) final { return &_loiterRadiusFact; }
Fact* landingAltitude (void) final { return &_landingAltitudeFact; }
Fact* landingDistance (void) final { return &_landingDistanceFact; }
Fact* landingHeading (void) final { return &_landingHeadingFact; }
Fact* stopTakingPhotos (void) final { return &_stopTakingPhotosFact; }
Fact* stopTakingVideo (void) final { return &_stopTakingVideoFact; }
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
static MissionItem* createDoLandStartItem (int seqNum, QObject* parent);
static MissionItem* createLoiterToAltItem (int seqNum, bool altRel, double loiterRaidus, double lat, double lon, double alt, QObject* parent);
static MissionItem* createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent);
// Overrides from ComplexMissionItem
QString patternName (void) const final { return name; }
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
QString mapVisualQML (void) const final { return QStringLiteral("VTOLLandingPatternMapVisual.qml"); }
// 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;
bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return "Landing Pattern"; }
QString commandName (void) const final { return "Landing Pattern"; }
QString abbreviation (void) const final { return "L"; }
QGeoCoordinate coordinate (void) const final { return _loiterCoordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _landingCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
double additionalTimeDelay (void) const final { return 0; }
ReadyForSaveState readyForSaveState (void) const final;
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final { setLoiterCoordinate(coordinate); }
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonArray& missionItems) final;
double amslEntryAlt (void) const final;
double amslExitAlt (void) const final;
double minAMSLAltitude (void) const final { return amslExitAlt(); }
double maxAMSLAltitude (void) const final { return amslEntryAlt(); }
static const QString name;
static const char* jsonComplexItemTypeValue;
static const char* settingsGroup;
static const char* loiterToLandDistanceName;
static const char* loiterAltitudeName;
static const char* loiterRadiusName;
static const char* landingHeadingName;
static const char* landingAltitudeName;
static const char* stopTakingPhotosName;
static const char* stopTakingVideoName;
private slots:
void _updateLoiterCoodinateAltitudeFromFact (void);
void _updateLandingCoodinateAltitudeFromFact (void);
double _mathematicAngleToHeading (double angle);
double _headingToMathematicAngle (double heading);
void _setDirty (void);
void _signalLastSequenceNumberChanged (void);
private:
void _calcGlideSlope(void) final;
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView, QObject* parent) { return new VTOLLandingComplexItem(masterController, flyView, parent); }
static bool _isValidLandItem(const MissionItem& missionItem);
// Overrides from LandingComplexItem
const Fact* _finalApproachAltitude (void) const final { return &_finalApproachAltitudeFact; }
const Fact* _loiterRadius (void) const final { return &_loiterRadiusFact; }
const Fact* _loiterClockwise (void) const final { return &_loiterClockwiseFact; }
const Fact* _landingAltitude (void) const final { return &_landingAltitudeFact; }
const Fact* _landingDistance (void) const final { return &_landingDistanceFact; }
const Fact* _landingHeading (void) const final { return &_landingHeadingFact; }
const Fact* _useLoiterToAlt (void) const final { return &_useLoiterToAltFact; }
const Fact* _stopTakingPhotos (void) const final { return &_stopTakingPhotosFact; }
const Fact* _stopTakingVideo (void) const final { return &_stopTakingVideoFact; }
void _calcGlideSlope (void) final;
MissionItem* _createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent) final;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _landingDistanceFact;
Fact _loiterAltitudeFact;
Fact _finalApproachAltitudeFact;
Fact _loiterRadiusFact;
Fact _loiterClockwiseFact;
Fact _landingHeadingFact;
Fact _landingAltitudeFact;
Fact _useLoiterToAltFact;
Fact _stopTakingPhotosFact;
Fact _stopTakingVideoFact;
static const char* _jsonLoiterCoordinateKey;
static const char* _jsonLoiterRadiusKey;
static const char* _jsonLoiterClockwiseKey;
static const char* _jsonLandingCoordinateKey;
static const char* _jsonAltitudesAreRelativeKey;
static const char* _jsonStopTakingPhotosKey;
static const char* _jsonStopTakingVideoKey;
friend VTOLLandingPatternTest;
};
......@@ -5,7 +5,7 @@
[
{
"name": "LandingDistance",
"shortDesc": "Distance between landing and loiter points.",
"shortDesc": "Distance between landing and approach points.",
"type": "double",
"units": "m",
"min": 10,
......@@ -14,7 +14,7 @@
},
{
"name": "LandingHeading",
"shortDesc": "Heading from loiter point to land point.",
"shortDesc": "Heading from approach to land point.",
"type": "double",
"units": "deg",
"min": 0.0,
......@@ -23,8 +23,8 @@
"default": 270.0
},
{
"name": "LoiterAltitude",
"shortDesc": "Aircraft will proceed to the loiter point and loiter downwards until it reaches this approach altitude. Once altitude is reached the aircraft will fly to land point at current altitude.",
"name": "FinalApproachAltitude",
"shortDesc": "Altitude to begin landing approach from.",
"type": "double",
"units": "m",
"decimalPlaces": 1,
......@@ -39,6 +39,12 @@
"units": "m",
"default": 75.0
},
{
"name": "LoiterClockwise",
"shortDesc": "Loiter clockwise around the final approach point.",
"type": "bool",
"default": true
},
{
"name": "LandingAltitude",
"shortDesc": "Altitude for landing point on ground.",
......@@ -47,6 +53,12 @@
"decimalPlaces": 1,
"default": 0.0
},
{
"name": "UseLoiterToAlt",
"shortDesc": "Use a loiter to altitude item for final appoach. Otherwise use a regular waypoint.",
"type": "bool",
"default": true
},
{
"name": "StopTakingPhotos",
"shortDesc": "Stop taking photos",
......
......@@ -55,10 +55,10 @@ void VisualMissionItemTest::cleanup(void)
_masterController->deleteLater();
}
void VisualMissionItemTest::_createSpy(SimpleMissionItem* simpleItem, MultiSignalSpy** visualSpy)
void VisualMissionItemTest::_createSpy(VisualMissionItem* visualItem, MultiSignalSpy** visualSpy)
{
*visualSpy = nullptr;
MultiSignalSpy* spy = new MultiSignalSpy();
QCOMPARE(spy->init(simpleItem, rgVisualItemSignals, cVisualItemSignals), true);
QCOMPARE(spy->init(visualItem, rgVisualItemSignals, cVisualItemSignals), true);
*visualSpy = spy;
}
......@@ -30,7 +30,7 @@ public:
void cleanup(void) override;
protected:
void _createSpy(SimpleMissionItem* simpleItem, MultiSignalSpy** visualSpy);
void _createSpy(VisualMissionItem* visualItem, MultiSignalSpy** visualSpy);
enum {
altDifferenceChangedIndex = 0,
......
......@@ -52,20 +52,26 @@ Rectangle {
visible: !editorColumnNeedLandingPoint.visible
SectionHeader {
id: loiterPointSection
id: finalApproachSection
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("Loiter point")
text: qsTr("Final approach")
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: loiterPointSection.checked
visible: finalApproachSection.checked
Item { width: 1; height: _spacer }
FactCheckBox {
text: qsTr("Use loiter to altitude")
fact: missionItem.useLoiterToAlt
visible: missionItem.useLoiterToAlt.visible
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
......@@ -75,24 +81,28 @@ Rectangle {
AltitudeFactTextField {
Layout.fillWidth: true
fact: missionItem.loiterAltitude
fact: missionItem.finalApproachAltitude
altitudeMode: _altitudeMode
}
QGCLabel { text: qsTr("Radius") }
QGCLabel {
text: qsTr("Radius")
visible: missionItem.useLoiterToAlt.rawValue
}
FactTextField {
Layout.fillWidth: true
fact: missionItem.loiterRadius
visible: missionItem.useLoiterToAlt.rawValue
}
}
Item { width: 1; height: _spacer }
QGCCheckBox {
text: qsTr("Loiter clockwise")
checked: missionItem.loiterClockwise
onClicked: missionItem.loiterClockwise = checked
FactCheckBox {
text: qsTr("Loiter clockwise")
fact: missionItem.loiterClockwise
visible: missionItem.useLoiterToAlt.rawValue
}
QGCButton {
......@@ -139,7 +149,7 @@ Rectangle {
QGCRadioButton {
id: specifyLandingDistance
text: qsTr("Landing Dist")
text: qsTr("Distance")
checked: missionItem.valueSetIsDistance.rawValue
onClicked: missionItem.valueSetIsDistance.rawValue = checked
Layout.fillWidth: true
......
This diff is collapsed.
......@@ -51,29 +51,27 @@ Rectangle {
spacing: _margin
visible: !editorColumnNeedLandingPoint.visible
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Loiter down to specified altitude. Fly to land point while transitioning. Hover straight down to land.")
}
SectionHeader {
id: loiterPointSection
id: finalApproachSection
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("Loiter point")
text: qsTr("Final approach")
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: loiterPointSection.checked
visible: finalApproachSection.checked
Item { width: 1; height: _spacer }
FactCheckBox {
text: qsTr("Use loiter to altitude")
fact: missionItem.useLoiterToAlt
visible: missionItem.useLoiterToAlt.visible
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
......@@ -83,24 +81,28 @@ Rectangle {
AltitudeFactTextField {
Layout.fillWidth: true
fact: missionItem.loiterAltitude
fact: missionItem.finalApproachAltitude
altitudeMode: _altitudeMode
}
QGCLabel { text: qsTr("Radius") }
QGCLabel {
text: qsTr("Radius")
visible: missionItem.useLoiterToAlt.rawValue
}
FactTextField {
Layout.fillWidth: true
fact: missionItem.loiterRadius
visible: missionItem.useLoiterToAlt.rawValue
}
}
Item { width: 1; height: _spacer }
QGCCheckBox {
text: qsTr("Loiter clockwise")
checked: missionItem.loiterClockwise
onClicked: missionItem.loiterClockwise = checked
FactCheckBox {
text: qsTr("Loiter clockwise")
fact: missionItem.loiterClockwise
visible: missionItem.useLoiterToAlt.rawValue
}
QGCButton {
......@@ -222,7 +224,7 @@ Rectangle {
wrapMode: Text.WordWrap
color: qgcPal.warningText
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("* Avoid tailwind from loiter to land.")
text: qsTr("* Avoid tailwind on approach to land.")
}
QGCLabel {
......
......@@ -33,9 +33,10 @@ Item {
property var _mouseArea
property var _dragAreas: [ ]
property var _flightPath
property real _landingAreaBearing: _missionItem.landingCoordinate.azimuthTo(_missionItem.loiterTangentCoordinate)
property var _loiterPointObject
property var _landingPointObject
property bool _useLoiterToAlt: _missionItem.useLoiterToAlt.rawValue
property real _landingAreaBearing: _missionItem.landingCoordinate.azimuthTo(_useLoiterToAlt ? _missionItem.loiterTangentCoordinate : _missionItem.finalApproachCoordinate)
function hideItemVisuals() {
objMgr.destroyObjects()
......@@ -43,7 +44,7 @@ Item {
function showItemVisuals() {
if (objMgr.rgDynamicObjects.length === 0) {
_loiterPointObject = objMgr.createObject(loiterPointComponent, map, true /* parentObjectIsMap */)
_loiterPointObject = objMgr.createObject(finalApproachPointComponent, map, true /* parentObjectIsMap */)
_landingPointObject = objMgr.createObject(landingPointComponent, map, true /* parentObjectIsMap */)
var rgComponents = [ flightPathComponent, loiterRadiusComponent ]
......@@ -80,7 +81,11 @@ Item {
}
function _setFlightPath() {
_flightPath = [ _missionItem.loiterTangentCoordinate, _missionItem.landingCoordinate ]
if (_useLoiterToAlt) {
_flightPath = [ _missionItem.loiterTangentCoordinate, _missionItem.landingCoordinate ]
} else {
_flightPath = [ _missionItem.finalApproachCoordinate, _missionItem.landingCoordinate ]
}
}
QGCDynamicObjectManager {
......@@ -105,6 +110,8 @@ Item {
hideItemVisuals()
}
on_UseLoiterToAltChanged: _setFlightPath()
Connections {
target: _missionItem
......@@ -141,6 +148,7 @@ Item {
onLandingCoordinateChanged: _setFlightPath()
onLoiterTangentCoordinateChanged: _setFlightPath()
onFinalApproachCoordinateChanged: _setFlightPath()
}
// Mouse area to capture landing point coordindate
......@@ -164,16 +172,28 @@ Item {
}
}
// Control which is used to drag the loiter point
// Control which is used to drag the final approach point
Component {
id: loiterDragAreaComponent
MissionItemIndicatorDrag {
mapControl: _root.map
itemIndicator: _loiterPointObject
itemCoordinate: _missionItem.loiterCoordinate
onItemCoordinateChanged: _missionItem.loiterCoordinate = itemCoordinate
itemCoordinate: _missionItem.finalApproachCoordinate
property bool _preventReentrancy: false
onItemCoordinateChanged: {
if (!_preventReentrancy) {
if (Drag.active) {
_preventReentrancy = true
var angle = _missionItem.landingCoordinate.azimuthTo(itemCoordinate)
var distance = _missionItem.landingCoordinate.distanceTo(_missionItem.finalApproachCoordinate)
_missionItem.finalApproachCoordinate = _missionItem.landingCoordinate.atDistanceAndAzimuth(distance, angle)
_preventReentrancy = false
}
}
}
}
}
......@@ -202,20 +222,20 @@ Item {
}
}
// Loiter point
// Final approach point
Component {
id: loiterPointComponent
id: finalApproachPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.loiterCoordinate
coordinate: _missionItem.finalApproachCoordinate
sourceItem:
MissionItemIndexLabel {
index: _missionItem.sequenceNumber
label: qsTr("Loiter")
label: _useLoiterToAlt ? qsTr("Loiter") : qsTr("Approach")
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
......@@ -249,11 +269,12 @@ Item {
MapCircle {
z: QGroundControl.zOrderMapItems
center: _missionItem.loiterCoordinate
center: _missionItem.finalApproachCoordinate
radius: _missionItem.loiterRadius.rawValue
border.width: 2
border.color: "green"
color: "transparent"
visible: _useLoiterToAlt
}
}
}
......@@ -59,7 +59,7 @@ bool MultiSignalSpy::init(QObject* signalEmitter, ///< [in] object whi
for (size_t i=0; i<_cSignals; i++) {
_rgSpys[i] = new QSignalSpy(_signalEmitter, _rgSignals[i]);
if (!_rgSpys[i]->isValid()) {
qDebug() << "Invalid signal";
qDebug() << "Invalid signal: index" << i;
return false;
}
}
......
......@@ -525,3 +525,8 @@ bool UnitTest::fuzzyCompareLatLon(const QGeoCoordinate& coord1, const QGeoCoordi
{
return coord1.distanceTo(coord2) < 1.0;
}
QGeoCoordinate UnitTest::changeCoordinateValue(const QGeoCoordinate& coordinate)
{
return coordinate.atDistanceAndAzimuth(1, 0);
}
......@@ -100,6 +100,8 @@ public:
/// @param increment 0 use standard increment, other increment by specified amount if double value
void changeFactValue(Fact* fact, double increment = 0);
QGeoCoordinate changeCoordinateValue(const QGeoCoordinate& coordinate);
/// Returns true is the position of the two coordinates is less then a meter from each other.
/// Does not check altitude.
static bool fuzzyCompareLatLon(const QGeoCoordinate& coord1, const QGeoCoordinate& coord2);
......
......@@ -49,6 +49,7 @@
#include "InitialConnectTest.h"
#include "FTPManagerTest.h"
#include "MissionCommandTreeEditorTest.h"
#include "LandingComplexItemTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
......@@ -84,6 +85,7 @@ UT_REGISTER_TEST(TransectStyleComplexItemTest)
UT_REGISTER_TEST(QGCMapPolylineTest)
UT_REGISTER_TEST(CameraCalcTest)
UT_REGISTER_TEST(FWLandingPatternTest)
UT_REGISTER_TEST(LandingComplexItemTest)
UT_REGISTER_TEST_STANDALONE(MissionCommandTreeEditorTest)
// List of unit test which are currently disabled.
......
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