Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Various Landing Pattern fixes and add final approach speed #12238

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/FactSystem/FactControls/FactCheckBox.qml
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@ QGCCheckBox {
Binding on checkState {
value: fact ?
(fact.typeIsBool ?
(fact.value === false ? Qt.Unchecked : Qt.Checked) :
(fact.value === 0 ? Qt.Unchecked : Qt.Checked)) :
(fact.value ? Qt.Checked : Qt.Unchecked) :
(fact.value !== 0 ? Qt.Checked : Qt.Unchecked)) :
Qt.Unchecked
}

Expand Down
15 changes: 15 additions & 0 deletions src/MissionManager/FWLandingPattern.FactMetaData.json
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,21 @@
"decimalPlaces": 1,
"default": 40.0
},
{
"name": "UseDoChangeSpeed",
"shortDesc": "Command a specific speed for the approach, useful for reducing energy before the glide slope.",
"type": "bool",
"default": false
},
{
"name": "FinalApproachSpeed",
"shortDesc": "Speed to perform the approach at.",
"type": "double",
"units": "m/s",
"min": 0.0,
"decimalPlaces": 1,
"default": 9.0
},
{
"name": "LoiterRadius",
"shortDesc": "Loiter radius.",
Expand Down
5 changes: 4 additions & 1 deletion src/MissionManager/FixedWingLandingComplexItem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* m
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
, _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])
, _useDoChangeSpeedFact (settingsGroup, _metaDataMap[useDoChangeSpeedName])
, _finalApproachSpeedFact (settingsGroup, _metaDataMap[finalApproachSpeedName])
, _loiterRadiusFact (settingsGroup, _metaDataMap[loiterRadiusName])
, _loiterClockwiseFact (settingsGroup, _metaDataMap[loiterClockwiseName])
, _landingHeadingFact (settingsGroup, _metaDataMap[landingHeadingName])
Expand Down Expand Up @@ -139,7 +141,8 @@ bool FixedWingLandingComplexItem::_isValidLandItem(const MissionItem& missionIte
{
if (missionItem.command() != MAV_CMD_NAV_LAND ||
!(missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItem.frame() == MAV_FRAME_GLOBAL) ||
missionItem.param1() != 0 || missionItem.param2() != 0 || missionItem.param3() != 0 || missionItem.param4() != 0) {
// ArduPilot automatically sets param4 to 1, so we have to allow for it.
missionItem.param1() != 0 || missionItem.param2() != 0 || missionItem.param3() != 0 || (missionItem.param4() != 0 && missionItem.param4() != 1)) {
return false;
} else {
return true;
Expand Down
4 changes: 4 additions & 0 deletions src/MissionManager/FixedWingLandingComplexItem.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,8 @@ private slots:

// Overrides from LandingComplexItem
const Fact* _finalApproachAltitude (void) const final { return &_finalApproachAltitudeFact; }
const Fact* _useDoChangeSpeed (void) const final { return &_useDoChangeSpeedFact; }
const Fact* _finalApproachSpeed (void) const final { return &_finalApproachSpeedFact; }
const Fact* _loiterRadius (void) const final { return &_loiterRadiusFact; }
const Fact* _loiterClockwise (void) const final { return &_loiterClockwiseFact; }
const Fact* _landingAltitude (void) const final { return &_landingAltitudeFact; }
Expand All @@ -80,6 +82,8 @@ private slots:

Fact _landingDistanceFact;
Fact _finalApproachAltitudeFact;
Fact _useDoChangeSpeedFact;
Fact _finalApproachSpeedFact;
Fact _loiterRadiusFact;
Fact _loiterClockwiseFact;
Fact _landingHeadingFact;
Expand Down
67 changes: 64 additions & 3 deletions src/MissionManager/LandingComplexItem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,8 @@ void LandingComplexItem::_init(void)
connect(useLoiterToAlt(), &Fact::rawValueChanged, this, &LandingComplexItem::_recalcFromCoordinateChange);

connect(finalApproachAltitude(), &Fact::valueChanged, this, &LandingComplexItem::_setDirty);
connect(useDoChangeSpeed(), &Fact::valueChanged, this, &LandingComplexItem::_setDirty);
connect(finalApproachSpeed(), &Fact::valueChanged, this, &LandingComplexItem::_setDirty);
connect(landingAltitude(), &Fact::valueChanged, this, &LandingComplexItem::_setDirty);
connect(landingDistance(), &Fact::valueChanged, this, &LandingComplexItem::_setDirty);
connect(landingHeading(), &Fact::valueChanged, this, &LandingComplexItem::_setDirty);
Expand Down Expand Up @@ -282,6 +284,10 @@ void LandingComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject*
MissionItem* item = _createDoLandStartItem(seqNum++, missionItemParent);
items.append(item);

if (useDoChangeSpeed()->rawValue().toBool()) {
item = _createDoChangeSpeedItem(0, finalApproachSpeed()->rawValue().toDouble(), 0, seqNum++, missionItemParent);
items.append(item);
}

if (stopTakingPhotos()->rawValue().toBool()) {
CameraSection::appendStopTakingPhotos(items, seqNum, missionItemParent);
Expand Down Expand Up @@ -312,6 +318,18 @@ MissionItem* LandingComplexItem::_createDoLandStartItem(int seqNum, QObject* par
parent);
}

MissionItem* LandingComplexItem::_createDoChangeSpeedItem(int speedType, int speedValue, int throttlePercentage, int seqNum, QObject* parent)
{
return new MissionItem(seqNum++, // sequence number
MAV_CMD_DO_CHANGE_SPEED, // MAV_CMD
MAV_FRAME_MISSION, // MAV_FRAME
speedType, speedValue, throttlePercentage, // param 1-3
0.0, 0.0, 0.0, 0.0, // param 4-7
true, // autoContinue
false, // isCurrentItem
parent);
}

MissionItem* LandingComplexItem::_createFinalApproachItem(int seqNum, QObject* parent)
{
if (useLoiterToAlt()->rawValue().toBool()) {
Expand Down Expand Up @@ -355,6 +373,7 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV

// A valid landing pattern is comprised of the follow commands in this order at the end of the item list:
// MAV_CMD_DO_LAND_START - required
// MAV_CMD_DO_CHANGE_SPEED - optional
// Stop taking photos sequence - optional
// Stop taking video sequence - optional
// MAV_CMD_NAV_LOITER_TO_ALT or MAV_CMD_NAV_WAYPOINT
Expand Down Expand Up @@ -388,13 +407,15 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV
MissionItem& missionItemFinalApproach = item->missionItem();
if (missionItemFinalApproach.command() == MAV_CMD_NAV_LOITER_TO_ALT) {
if (missionItemFinalApproach.frame() != landPointFrame ||
missionItemFinalApproach.param1() != 1.0 || missionItemFinalApproach.param3() != 0 || missionItemFinalApproach.param4() != 1.0) {
(masterController->managerVehicle()->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA ?
missionItemFinalApproach.param1() != 0.0 : missionItemFinalApproach.param1() != 1.0) ||
missionItemFinalApproach.param3() != 0 || missionItemFinalApproach.param4() != 1.0) {
return false;
}
} else if (missionItemFinalApproach.command() == MAV_CMD_NAV_WAYPOINT) {
if (missionItemFinalApproach.frame() != landPointFrame ||
missionItemFinalApproach.param1() != 0 || missionItemFinalApproach.param2() != 0 || missionItemFinalApproach.param3() != 0 ||
!qIsNaN(missionItemFinalApproach.param4()) ||
(masterController->managerVehicle()->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA && !qIsNaN(missionItemFinalApproach.param4())) ||
qIsNaN(missionItemFinalApproach.param5()) || qIsNaN(missionItemFinalApproach.param6()) || qIsNaN(missionItemFinalApproach.param6())) {
return false;
}
Expand All @@ -415,6 +436,27 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV
scanIndex += CameraSection::stopTakingPhotosCommandCount();
}

scanIndex--;
bool useDoChangeSpeed = false;
double finalApproachSpeed = 0;
if (scanIndex >= 0 && scanIndex < visualItems->count()) {
item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItemChangeSpeed = item->missionItem();
if (missionItemChangeSpeed.command() == MAV_CMD_DO_CHANGE_SPEED &&
missionItemChangeSpeed.param1() >= 0 && missionItemChangeSpeed.param1() <= 3 &&
missionItemChangeSpeed.param2() >= 0 &&
missionItemChangeSpeed.param3() >= 0 && missionItemChangeSpeed.param3() <= 100 &&
missionItemChangeSpeed.param4() == 0) {
useDoChangeSpeed = true;
finalApproachSpeed = missionItemChangeSpeed.param2();
}
}
}
if (!useDoChangeSpeed) {
scanIndex++;
}

scanIndex--;
if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
return false;
Expand All @@ -425,7 +467,9 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV
}
MissionItem& missionItemDoLandStart = item->missionItem();
if (missionItemDoLandStart.command() != MAV_CMD_DO_LAND_START ||
missionItemDoLandStart.frame() != MAV_FRAME_MISSION ||
(masterController->managerVehicle()->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA ?
missionItemDoLandStart.frame() != MAV_FRAME_GLOBAL :
missionItemDoLandStart.frame() != MAV_FRAME_MISSION) ||
missionItemDoLandStart.param1() != 0 || missionItemDoLandStart.param2() != 0 || missionItemDoLandStart.param3() != 0 || missionItemDoLandStart.param4() != 0 ||
missionItemDoLandStart.param5() != 0 || missionItemDoLandStart.param6() != 0 || missionItemDoLandStart.param7() != 0) {
return false;
Expand All @@ -440,6 +484,9 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV
if (stopTakingVideo) {
deleteCount += CameraSection::stopTakingVideoCommandCount();
}
if (useDoChangeSpeed) {
deleteCount++;
}
int firstItem = visualItems->count() - deleteCount;
while (deleteCount--) {
visualItems->removeAt(firstItem)->deleteLater();
Expand All @@ -454,8 +501,12 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV
complexItem->_altitudesAreRelative = landPointFrame == MAV_FRAME_GLOBAL_RELATIVE_ALT;
complexItem->setFinalApproachCoordinate(QGeoCoordinate(missionItemFinalApproach.param5(), missionItemFinalApproach.param6()));
complexItem->finalApproachAltitude()->setRawValue(missionItemFinalApproach.param7());
complexItem->useDoChangeSpeed()->setRawValue(useDoChangeSpeed);
complexItem->useLoiterToAlt()->setRawValue(useLoiterToAlt);

if (useDoChangeSpeed) {
complexItem->finalApproachSpeed()->setRawValue(finalApproachSpeed);
}
if (useLoiterToAlt) {
complexItem->loiterRadius()->setRawValue(qAbs(missionItemFinalApproach.param2()));
complexItem->loiterClockwise()->setRawValue(missionItemFinalApproach.param2() > 0);
Expand Down Expand Up @@ -558,6 +609,9 @@ QJsonObject LandingComplexItem::_save(void)
JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
saveObject[_jsonFinalApproachCoordinateKey] = jsonCoordinate;

saveObject[_jsonUseDoChangeSpeedKey] = useDoChangeSpeed()->rawValue().toBool();
saveObject[_jsonFinalApproachSpeedKey] = finalApproachSpeed()->rawValue().toDouble();

coordinate = _landingCoordinate;
coordinate.setAltitude(landingAltitude()->rawValue().toDouble());
JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
Expand All @@ -581,6 +635,8 @@ bool LandingComplexItem::_load(const QJsonObject& complexObject, int sequenceNum
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ _jsonDeprecatedLoiterCoordinateKey, QJsonValue::Array, false }, // Loiter changed to Final Approach
{ _jsonFinalApproachCoordinateKey, QJsonValue::Array, false },
{ _jsonUseDoChangeSpeedKey, QJsonValue::Bool, false },
{ _jsonFinalApproachSpeedKey, QJsonValue::Double, false },
{ _jsonLoiterRadiusKey, QJsonValue::Double, true },
{ _jsonLoiterClockwiseKey, QJsonValue::Bool, true },
{ _jsonLandingCoordinateKey, QJsonValue::Array, true },
Expand Down Expand Up @@ -650,6 +706,11 @@ bool LandingComplexItem::_load(const QJsonObject& complexObject, int sequenceNum
_finalApproachCoordinate = coordinate;
finalApproachAltitude()->setRawValue(coordinate.altitude());

useDoChangeSpeed()->setRawValue(complexObject[_jsonUseDoChangeSpeedKey].toBool(false));
finalApproachSpeed()->setRawValue(complexObject.contains(_jsonFinalApproachSpeedKey)
? complexObject[_jsonFinalApproachSpeedKey].toDouble()
: finalApproachSpeed()->rawDefaultValue());

if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
return false;
}
Expand Down
Loading
Loading