Skip to content

Commit

Permalink
Add support to set Land Start coords to next item
Browse files Browse the repository at this point in the history
Added an option in the Plan View settings to automatically set the
coordinates of DO_LAND_START mission items to match the next waypoint in
the mission. This is used to help find the closest landing sequence in
the event of an RTL. This option is disabled by default to match the
previous behavior.
  • Loading branch information
rubenp02 committed Jan 9, 2025
1 parent 2647246 commit ce1f246
Show file tree
Hide file tree
Showing 6 changed files with 46 additions and 1 deletion.
29 changes: 29 additions & 0 deletions src/MissionManager/MissionController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -272,6 +272,9 @@ void MissionController::addMissionToKML(KMLPlanDomDocument& planKML)
QList<MissionItem*> rgMissionItems;

_convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
if (_planViewSettings->autoSetDoLandStartCoords()->rawValue().toBool())
_autoSetDoLandStartCoords(rgMissionItems);

planKML.addMission(_controllerVehicle, _visualItems, rgMissionItems);
deleteParent->deleteLater();
}
Expand All @@ -282,6 +285,8 @@ void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel*
QList<MissionItem*> rgMissionItems;

_convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
if (_planViewSettings->autoSetDoLandStartCoords()->rawValue().toBool())
_autoSetDoLandStartCoords(rgMissionItems);

// PlanManager takes control of MissionItems so no need to delete
vehicle->missionManager()->writeMissionItems(rgMissionItems);
Expand Down Expand Up @@ -2658,6 +2663,30 @@ void MissionController::_firstItemAdded(void)
_controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
}

void MissionController::_autoSetDoLandStartCoords(QList<MissionItem*>& rgMissionItems) {
for (int i = 0; i < rgMissionItems.count(); i++) {
MissionItem* item = rgMissionItems[i];
if (item->command() == MAV_CMD_DO_LAND_START) {
MissionItem* nextItemWCoords = nullptr;
// We only modify the coordinates if there is another item with valid coordinates after
for (int j = i + 1; j < rgMissionItems.count(); j++) {
if (rgMissionItems[j]->coordinate().isValid() &&
(rgMissionItems[j]->frame() != MAV_FRAME_MISSION)) {
nextItemWCoords = rgMissionItems[j];
break;
}
}

if (nextItemWCoords) {
item->setFrame(nextItemWCoords->frame());
item->setParam5(nextItemWCoords->param5());
item->setParam6(nextItemWCoords->param6());
item->setParam7(nextItemWCoords->param7());
}
}
}
}

MissionController::SendToVehiclePreCheckState MissionController::sendToVehiclePreCheck(void)
{
if (_managerVehicle->isOfflineEditingVehicle()) {
Expand Down
3 changes: 2 additions & 1 deletion src/MissionManager/MissionController.h
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,7 @@ class MissionController : public PlanElementController
int readyForSaveState(void) const;

/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);

bool loadJsonFile(QFile& file, QString& errorString);
bool loadTextFile(QFile& file, QString& errorString);
Expand Down Expand Up @@ -359,6 +359,7 @@ private slots:
FlightPathSegment* _createFlightPathSegmentWorker (VisualItemPair& pair, bool mavlinkTerrainFrame);
void _allItemsRemoved (void);
void _firstItemAdded (void);
void _autoSetDoLandStartCoords (QList<MissionItem*>& rgMissionItems);

static double _calcDistanceToHome (VisualMissionItem* currentItem, VisualMissionItem* homeItem);
static double _normalizeLat (double lat);
Expand Down
6 changes: 6 additions & 0 deletions src/Settings/PlanView.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,12 @@
"type": "bool",
"default": false
},
{
"name": "autoSetDoLandStartCoords",
"shortDesc": "Automatically set the coordinates of Land Start items to the next waypoint",
"type": "bool",
"default": false
},
{
"name": "useConditionGate",
"shortDesc": "Use MAV_CMD_CONDITION_GATE for pattern generation",
Expand Down
1 change: 1 addition & 0 deletions src/Settings/PlanViewSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,5 +21,6 @@ DECLARE_SETTINGSFACT(PlanViewSettings, showMissionItemStatus)
DECLARE_SETTINGSFACT(PlanViewSettings, useConditionGate)
DECLARE_SETTINGSFACT(PlanViewSettings, takeoffItemNotRequired)
DECLARE_SETTINGSFACT(PlanViewSettings, allowMultipleLandingPatterns)
DECLARE_SETTINGSFACT(PlanViewSettings, autoSetDoLandStartCoords)
DECLARE_SETTINGSFACT(PlanViewSettings, showGimbalOnlyWhenSet)
DECLARE_SETTINGSFACT(PlanViewSettings, vtolTransitionDistance)
1 change: 1 addition & 0 deletions src/Settings/PlanViewSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ class PlanViewSettings : public SettingsGroup
DEFINE_SETTINGFACT(useConditionGate)
DEFINE_SETTINGFACT(takeoffItemNotRequired)
DEFINE_SETTINGFACT(allowMultipleLandingPatterns)
DEFINE_SETTINGFACT(autoSetDoLandStartCoords)
DEFINE_SETTINGFACT(showGimbalOnlyWhenSet)
DEFINE_SETTINGFACT(vtolTransitionDistance)
};
7 changes: 7 additions & 0 deletions src/UI/preferences/PlanViewSettings.qml
Original file line number Diff line number Diff line change
Expand Up @@ -58,5 +58,12 @@ SettingsPage {
fact: _planViewSettings.allowMultipleLandingPatterns
visible: fact.visible
}

FactCheckBoxSlider {
Layout.fillWidth: true
text: qsTr("Automatically set Land Start coordinates to the next waypoint")
fact: _planViewSettings.autoSetDoLandStartCoords
visible: fact.visible
}
}
}

0 comments on commit ce1f246

Please sign in to comment.