30#include <QtCore/QJsonArray>
31#include <QtCore/QJsonDocument>
34#define UPDATE_TIMEOUT 5000
40 , _controllerVehicle (masterController->controllerVehicle())
41 , _managerVehicle (masterController->managerVehicle())
42 , _missionManager (masterController->managerVehicle()->missionManager())
47 _resetMissionFlightStatus();
49 _updateTimer.setSingleShot(
true);
51 connect(&_updateTimer, &QTimer::timeout,
this, &MissionController::_updateTimeout);
52 connect(_planViewSettings->takeoffItemNotRequired(), &
Fact::rawValueChanged,
this, &MissionController::_forceRecalcOfAllowedBits);
71void MissionController::_resetMissionFlightStatus(
void)
73 _flightStatusCalc.
reset(_controllerVehicle, _managerVehicle, _missionContainsVTOLTakeoff);
74 _missionFlightStatus = _flightStatusCalc.
status();
89 qCDebug(MissionControllerLog) <<
"start flyView" << flyView;
91 _managerVehicleChanged(_managerVehicle);
98void MissionController::_init(
void)
101 _addMissionSettings(_visualItems);
106 _initAllVisualItems();
110void MissionController::_newMissionItemsAvailableFromVehicle(
bool removeAllRequested)
112 qCDebug(MissionControllerLog) <<
"_newMissionItemsAvailableFromVehicle flyView:count" <<
_flyView << _missionManager->
missionItems().count();
126 _setupNewVisualItems();
128 const QList<MissionItem*>& newMissionItems = _missionManager->
missionItems();
129 qCDebug(MissionControllerLog) <<
"loading from vehicle: count"<< newMissionItems.count();
135 if (fakeHomeItem->
coordinate().latitude() != 0 || fakeHomeItem->
coordinate().longitude() != 0) {
141 bool weHaveItemsFromVehicle =
false;
142 for (; i < newMissionItems.count(); i++) {
143 weHaveItemsFromVehicle =
true;
144 const MissionItem* missionItem = newMissionItems[i];
150 simpleItem->deleteLater();
151 simpleItem = _takeoffMissionItem;
153 _visualItems->
append(simpleItem);
161 _initAllVisualItems();
167 _itemsRequested =
false;
173 qCCritical(MissionControllerLog) <<
"MissionControllerLog::loadFromVehicle called while offline";
175 qCCritical(MissionControllerLog) <<
"MissionControllerLog::loadFromVehicle called while syncInProgress";
177 _itemsRequested =
true;
185 qCCritical(MissionControllerLog) <<
"MissionControllerLog::sendToVehicle called while offline";
187 qCCritical(MissionControllerLog) <<
"MissionControllerLog::sendToVehicle called while syncInProgress";
189 qCDebug(MissionControllerLog) <<
"MissionControllerLog::sendToVehicle";
190 if (_visualItems->
count() == 1) {
204bool MissionController::_convertToMissionItems(
QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
206 if (visualMissionItems->
count() == 0) {
210 bool endActionSet =
false;
213 for (
int i=0; i<visualMissionItems->
count(); i++) {
219 qCDebug(MissionControllerLog) <<
"_convertToMissionItems seqNum:lastSeqNum:command"
228 endActionSet = settingsItem->
addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
236 QObject* deleteParent =
new QObject();
237 QList<MissionItem*> rgMissionItems;
239 _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
240 planKML.
addMission(_controllerVehicle, _visualItems, rgMissionItems);
241 deleteParent->deleteLater();
247 QList<MissionItem*> rgMissionItems;
249 _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
256int MissionController::_nextSequenceNumber(
void)
258 if (_visualItems->
count() == 0) {
259 qWarning() <<
"Internal error: Empty visual item list";
267VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command,
int visualItemIndex,
bool makeCurrentItem)
269 int sequenceNumber = _nextSequenceNumber();
274 _initVisualItem(newItem);
281 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltFrame)) {
290 if (visualItemIndex == -1) {
291 _visualItems->
append(newItem);
293 _visualItems->
insert(visualItemIndex, newItem);
297 _recalcAllWithCoordinate(coordinate);
299 if (makeCurrentItem) {
311 return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_WAYPOINT, visualItemIndex, makeCurrentItem);
316 int sequenceNumber = _nextSequenceNumber();
319 _initVisualItem(_takeoffMissionItem);
325 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltFrame)) {
330 if (visualItemIndex == -1) {
331 _visualItems->
append(_takeoffMissionItem);
333 _visualItems->
insert(visualItemIndex, _takeoffMissionItem);
338 if (makeCurrentItem) {
344 return _takeoffMissionItem;
350 return _planViewSettings->allowMultipleLandingPatterns()
351 ->rawValue().toBool() &&
360 }
else if (_controllerVehicle->
vtol()) {
364 return _insertSimpleMissionItemWorker(coordinate, _controllerVehicle->
vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
370 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));
381 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE, visualItemIndex, makeCurrentItem));
401 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltFrame)) {
406 _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
418 _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
423void MissionController::_insertComplexMissionItemWorker(
const QGeoCoordinate& mapCenterCoordinate,
ComplexMissionItem* complexItem,
int visualItemIndex,
bool makeCurrentItem)
425 int sequenceNumber = _nextSequenceNumber();
426 bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
427 qobject_cast<CorridorScanComplexItem*>(complexItem) ||
428 qobject_cast<StructureScanComplexItem*>(complexItem);
430 if (surveyStyleItem) {
431 bool rollSupported =
false;
432 bool pitchSupported =
false;
433 bool yawSupported =
false;
441 if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
443 cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
447 if (_controllerVehicle->
firmwarePlugin()->
hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
449 if (!cameraSection->specifyGimbal()) {
450 cameraSection->setSpecifyGimbal(
true);
451 cameraSection->gimbalPitch()->setRawValue(-90.0);
457 if (!qobject_cast<VTOLLandingComplexItem*>(complexItem)) {
460 _initVisualItem(complexItem);
462 if (visualItemIndex == -1) {
463 _visualItems->
append(complexItem);
465 _visualItems->
insert(visualItemIndex, complexItem);
472 _recalcAllWithCoordinate(mapCenterCoordinate);
474 if (makeCurrentItem) {
482 return _visualItems ? _visualItems->
indexOf(
object) : -1;
487 if (viIndex <= 0 || viIndex >= _visualItems->
count()) {
488 qWarning() <<
"MissionController::removeVisualItem called with bad index - count:index" << _visualItems->
count() << viIndex;
495 if (item == _takeoffMissionItem) {
496 _takeoffMissionItem =
nullptr;
499 _deinitVisualItem(item);
502 if (removeSurveyStyle) {
504 bool foundSurvey =
false;
505 for (
int i=1; i<_visualItems->
count(); i++) {
514 bool rollSupported =
false;
515 bool pitchSupported =
false;
516 bool yawSupported =
false;
518 if (_controllerVehicle->
firmwarePlugin()->
hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
533 if (viIndex >= _visualItems->
count()) {
534 newVIIndex = _visualItems->
count() - 1;
536 newVIIndex = viIndex;
542 if (_visualItems->
count() == 1) {
552 _deinitAllVisualItems();
556 QTimer::singleShot(1000, oldItems, [oldItems] {
558 oldItems->deleteLater();
562 _settingsItem =
nullptr;
563 _takeoffMissionItem =
nullptr;
566 _visualItems = newItems;
567 if (_visualItems->
count() == 0) {
568 _addMissionSettings(_visualItems);
574 _addMissionSettings(_visualItems);
580 _setupNewVisualItems();
581 _initAllVisualItems();
583 _resetMissionFlightStatus();
590 QList<JsonParsing::KeyValidateInfo> rootKeyInfoList = {
591 { _jsonPlannedHomePositionKey, QJsonValue::Array,
true },
592 { _jsonItemsKey, QJsonValue::Array,
true },
593 { _jsonFirmwareTypeKey, QJsonValue::Double,
true },
594 { _jsonVehicleTypeKey, QJsonValue::Double,
false },
595 { _jsonCruiseSpeedKey, QJsonValue::Double,
false },
596 { _jsonHoverSpeedKey, QJsonValue::Double,
false },
597 { _jsonGlobalPlanAltitudeModeKey, QJsonValue::Double,
false },
605 qCDebug(MissionControllerLog) <<
"MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
610 MAV_AUTOPILOT planFileFirmwareType =
static_cast<MAV_AUTOPILOT
>(json[_jsonFirmwareTypeKey].toInt());
612 if (json.contains(_jsonVehicleTypeKey)) {
613 planFileVehicleType =
static_cast<MAV_TYPE
>(json[_jsonVehicleTypeKey].toInt());
618 appSettings->offlineEditingFirmwareClass()->setRawValue(
QGCMAVLink::firmwareClass(
static_cast<MAV_AUTOPILOT
>(json[_jsonFirmwareTypeKey].toInt())));
619 if (json.contains(_jsonVehicleTypeKey)) {
629 if (json.contains(_jsonCruiseSpeedKey)) {
630 appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
632 if (json.contains(_jsonHoverSpeedKey)) {
633 appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
635 if (json.contains(_jsonGlobalPlanAltitudeModeKey)) {
636 setGlobalAltitudeFrame(json[_jsonGlobalPlanAltitudeModeKey].toVariant().value<QGroundControlQmlGlobal::AltitudeFrame>());
639 QGeoCoordinate homeCoordinate;
646 qCDebug(MissionControllerLog) <<
"plannedHomePosition" << homeCoordinate;
650 int nextSequenceNumber = 1;
651 const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
652 for (
int i=0; i<rgMissionItems.count(); i++) {
654 const QJsonValue& itemValue = rgMissionItems[i];
655 if (!itemValue.isObject()) {
656 errorString = tr(
"Mission item %1 is not an object").arg(i);
659 const QJsonObject itemObject = itemValue.toObject();
663 QList<JsonParsing::KeyValidateInfo> itemKeyInfoList = {
678 simpleItem->deleteLater();
679 simpleItem = takeoffItem;
681 qCDebug(MissionControllerLog) <<
"Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->
command();
688 QList<JsonParsing::KeyValidateInfo> complexItemKeyInfoList = {
696 qCDebug(MissionControllerLog) <<
"Loading complex item type:" << complexItemType <<
"nextSequenceNumber:" << nextSequenceNumber;
699 errorString = tr(
"Unsupported complex item type: %1").arg(complexItemType);
702 if (!complexItem->
load(itemObject, nextSequenceNumber++,
errorString)) {
707 qCDebug(MissionControllerLog) <<
"Complex item load complete nextSequenceNumber:" << nextSequenceNumber;
710 errorString = tr(
"Unknown item type: %1").arg(itemType);
719 if (doJumpItem->
command() == MAV_CMD_DO_JUMP) {
733 errorString = tr(
"Could not find doJumpId: %1").arg(findDoJumpId);
745 bool firstItem =
true;
746 bool plannedHomePositionInFile =
false;
748 QString firstLine = stream.readLine();
749 const QStringList& version = firstLine.split(
" ");
751 bool versionOk =
false;
752 if (version.size() == 3 && version[0] ==
"QGC" && version[1] ==
"WPL") {
753 if (version[2] ==
"110") {
756 plannedHomePositionInFile =
true;
757 }
else if (version[2] ==
"120") {
760 plannedHomePositionInFile =
false;
767 while (!stream.atEnd()) {
769 if (item->
load(stream)) {
770 if (firstItem && plannedHomePositionInFile) {
783 errorString = tr(
"The mission file is corrupted.");
788 errorString = tr(
"The mission file is not compatible with this version of %1.").arg(QCoreApplication::applicationName());
792 if (!plannedHomePositionInFile) {
796 if (item && item->
command() == MAV_CMD_DO_JUMP) {
807 _setupNewVisualItems(loadedVisualItems);
811 _initAllVisualItems();
813 if (_visualItems->
count() > 1) {
823 QString errorMessage = tr(
"Mission: %1");
826 if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
830 _initLoadedVisualItems(loadedVisualItems);
838 QString errorMessage = tr(
"Mission: %1");
839 QByteArray bytes = file.readAll();
840 QTextStream stream(bytes);
845 if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
850 _initLoadedVisualItems(loadedVisualItems);
857 for (
int i=0; i<_visualItems->
count(); i++) {
875 qWarning() <<
"First item is not MissionSettingsItem";
878 QJsonValue coordinateValue;
880 json[_jsonPlannedHomePositionKey] = coordinateValue;
881 json[_jsonFirmwareTypeKey] = _controllerVehicle->
firmwareType();
882 json[_jsonVehicleTypeKey] = _controllerVehicle->
vehicleType();
885 json[_jsonGlobalPlanAltitudeModeKey] = _globalAltFrame;
889 QJsonArray rgJsonMissionItems;
890 for (
int i=0; i<_visualItems->
count(); i++) {
893 visualItem->
save(rgJsonMissionItems);
898 QList<MissionItem*> rgMissionItems;
900 if (_convertToMissionItems(_visualItems, rgMissionItems,
this )) {
901 QJsonObject saveObject;
902 MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
903 missionItem->
save(saveObject);
904 rgJsonMissionItems.append(saveObject);
906 for (
int i=0; i<rgMissionItems.count(); i++) {
907 rgMissionItems[i]->deleteLater();
911 json[_jsonItemsKey] = rgJsonMissionItems;
918 bool takeoffStraightUp = pair.second->isTakeoffItem() && !_controllerVehicle->
fixedWing();
920 QGeoCoordinate coord1 = pair.first->exitCoordinate();
921 QGeoCoordinate coord2 = pair.second->entryCoordinate();
922 double coord2AMSLAlt = pair.second->amslEntryAlt();
923 double coord1AMSLAlt = takeoffStraightUp ? coord2AMSLAlt : pair.first->amslExitAlt();
926 if (pair.second->isTakeoffItem()) {
928 }
else if (pair.second->isLandCommand()) {
934 if (takeoffStraightUp) {
961 _flightPathSegmentHashTable[pair] = segment = prevItemPairHashTable.take(pair);
963 segment = _createFlightPathSegmentWorker(pair, mavlinkTerrainFrame);
964 _flightPathSegmentHashTable[pair] = segment;
967 _simpleFlightPathSegments.
append(segment);
972void MissionController::_recalcFlightPathSegments(
void)
975 int segmentCount = 0;
976 bool firstCoordinateNotFound =
true;
978 bool linkEndToHome =
false;
979 bool linkStartToHome = _controllerVehicle->
rover() ? true :
false;
980 bool foundRTL =
false;
981 bool homePositionValid = _settingsItem->
coordinate().isValid();
982 bool roiActive =
false;
983 bool previousItemIsIncomplete =
false;
984 bool signalSplitSegmentChanged =
false;
986 qCDebug(MissionControllerLog) <<
"_recalcFlightPathSegments homePositionValid" << homePositionValid;
990 _missionContainsVTOLTakeoff =
false;
991 _flightPathSegmentHashTable.clear();
996 _simpleFlightPathSegments.
clear();
997 _directionArrows.
clear();
1004 for (
int i=1; i<_visualItems->
count(); i++) {
1005 qobject_cast<VisualMissionItem*>(_visualItems->
get(i))->clearSimpleFlighPathSegment();
1009 for (
int i=1; i<_visualItems->
count(); i++) {
1018 if (_isROICancelItem(simpleItem)) {
1022 if (_isROIBeginItem(simpleItem)) {
1029 case MAV_CMD_NAV_TAKEOFF:
1030 case MAV_CMD_NAV_VTOL_TAKEOFF:
1031 _missionContainsVTOLTakeoff = command == MAV_CMD_NAV_VTOL_TAKEOFF;
1032 if (!linkEndToHome) {
1035 if (firstCoordinateNotFound) {
1036 linkStartToHome =
true;
1040 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1041 linkEndToHome =
true;
1056 lastFlyThroughVI = visualItem;
1066 previousItemIsIncomplete =
true;
1067 }
else if (previousItemIsIncomplete) {
1069 previousItemIsIncomplete =
false;
1070 firstCoordinateNotFound =
false;
1071 lastFlyThroughVI = visualItem;
1073 if (lastFlyThroughVI != _settingsItem || (homePositionValid && linkStartToHome)) {
1074 bool addDirectionArrow =
false;
1080 addDirectionArrow =
true;
1081 }
else if (segmentCount > 5) {
1083 addDirectionArrow =
true;
1088 lastSegmentVisualItemPair =
VisualItemPair(lastFlyThroughVI, visualItem);
1089 SimpleMissionItem* lastSimpleItem = qobject_cast<SimpleMissionItem*>(lastFlyThroughVI);
1090 bool mavlinkTerrainFrame = lastSimpleItem ? lastSimpleItem->
missionItem().
frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT :
false;
1091 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair, mavlinkTerrainFrame);
1093 if (addDirectionArrow) {
1094 _directionArrows.
append(segment);
1096 if (visualItem->
isCurrentItem() && _delayedSplitSegmentUpdate) {
1097 _splitSegment = segment;
1098 _delayedSplitSegmentUpdate =
false;
1099 signalSplitSegmentChanged =
true;
1103 firstCoordinateNotFound =
false;
1104 lastFlyThroughVI = visualItem;
1109 if (linkEndToHome && lastFlyThroughVI != _settingsItem && homePositionValid) {
1110 lastSegmentVisualItemPair =
VisualItemPair(lastFlyThroughVI, _settingsItem);
1111 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair,
false );
1117 if (lastSegmentVisualItemPair.first) {
1123 if (_flightPathSegmentHashTable.contains(lastSegmentVisualItemPair)) {
1125 coordVector = _flightPathSegmentHashTable[lastSegmentVisualItemPair];
1126 }
else if (oldSegmentTable.contains(lastSegmentVisualItemPair)) {
1128 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector = oldSegmentTable.take(lastSegmentVisualItemPair);
1133 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->entryCoordinate() : lastSegmentVisualItemPair.first->exitCoordinate(),
1134 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->amslEntryAlt() : lastSegmentVisualItemPair.first->amslExitAlt(),
1135 lastSegmentVisualItemPair.second->entryCoordinate(),
1136 lastSegmentVisualItemPair.second->amslEntryAlt(),
1139 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector;
1142 _directionArrows.
append(coordVector);
1149 qDeleteAll(oldSegmentTable);
1154 if (signalSplitSegmentChanged) {
1159void MissionController::_recalcMissionFlightStatus()
1161 if (!_visualItems->
count()) {
1165 qCDebug(MissionControllerLog) <<
"_recalcMissionFlightStatus";
1167 _flightStatusCalc.
recalc(_visualItems, _settingsItem, _controllerVehicle, _managerVehicle, _appSettings, _planViewSettings, _missionContainsVTOLTakeoff);
1168 _missionFlightStatus = _flightStatusCalc.
status();
1191void MissionController::_recalcSequence(
void)
1193 if (_inRecalcSequence) {
1200 _inRecalcSequence =
true;
1201 int sequenceNumber = 0;
1202 for (
int i=0; i<_visualItems->
count(); i++) {
1207 _inRecalcSequence =
false;
1211void MissionController::_recalcChildItems(
void)
1217 for (
int i=1; i<_visualItems->
count(); i++) {
1226 currentParentItem = item;
1237void MissionController::_setupTreeModel(
void)
1241 _visualItemsTree.
clear();
1244 _planFileGroupNode.setObjectName(tr(
"Plan Info"));
1245 _visualItemsTree.
appendItem(&_planFileGroupNode, QModelIndex(), QStringLiteral(
"planFileGroup"));
1247 _planFileInfoMarker.setObjectName(QStringLiteral(
"planFileInfo"));
1248 _visualItemsTree.
appendItem(&_planFileInfoMarker,
1249 _visualItemsTree.
indexForObject(&_planFileGroupNode), QStringLiteral(
"planFileInfo"));
1252 _defaultsGroupNode.setObjectName(tr(
"Defaults"));
1253 _visualItemsTree.
appendItem(&_defaultsGroupNode, QModelIndex(), QStringLiteral(
"defaultsGroup"));
1255 _defaultsInfoMarker.setObjectName(QStringLiteral(
"defaultsInfo"));
1256 _visualItemsTree.
appendItem(&_defaultsInfoMarker,
1257 _visualItemsTree.
indexForObject(&_defaultsGroupNode), QStringLiteral(
"defaultsInfo"));
1260 _missionItemsGroupNode.setObjectName(tr(
"Mission Items"));
1261 _visualItemsTree.
appendItem(&_missionItemsGroupNode, QModelIndex(), QStringLiteral(
"missionGroup"));
1264 _fenceGroupNode.setObjectName(tr(
"GeoFence"));
1265 _visualItemsTree.
appendItem(&_fenceGroupNode, QModelIndex(), QStringLiteral(
"fenceGroup"));
1268 _fenceEditorMarker.setObjectName(QStringLiteral(
"fenceEditor"));
1269 _visualItemsTree.
appendItem(&_fenceEditorMarker,
1270 _visualItemsTree.
indexForObject(&_fenceGroupNode), QStringLiteral(
"fenceEditor"));
1273 _rallyGroupNode.setObjectName(tr(
"Rally Points"));
1274 _visualItemsTree.
appendItem(&_rallyGroupNode, QModelIndex(), QStringLiteral(
"rallyGroup"));
1277 _rallyHeaderMarker.setObjectName(QStringLiteral(
"rallyHeader"));
1278 _visualItemsTree.
appendItem(&_rallyHeaderMarker,
1279 _visualItemsTree.
indexForObject(&_rallyGroupNode), QStringLiteral(
"rallyHeader"));
1282 _transformGroupNode.setObjectName(tr(
"Transform"));
1283 _visualItemsTree.
appendItem(&_transformGroupNode, QModelIndex(), QStringLiteral(
"transformGroup"));
1286 _transformEditorMarker.setObjectName(QStringLiteral(
"transformEditor"));
1287 _visualItemsTree.
appendItem(&_transformEditorMarker,
1288 _visualItemsTree.
indexForObject(&_transformGroupNode), QStringLiteral(
"transformEditor"));
1293 _planFileGroupIndex = QPersistentModelIndex(_visualItemsTree.
indexForObject(&_planFileGroupNode));
1294 _defaultsGroupIndex = QPersistentModelIndex(_visualItemsTree.
indexForObject(&_defaultsGroupNode));
1295 _missionGroupIndex = QPersistentModelIndex(_visualItemsTree.
indexForObject(&_missionItemsGroupNode));
1296 _fenceGroupIndex = QPersistentModelIndex(_visualItemsTree.
indexForObject(&_fenceGroupNode));
1297 _rallyGroupIndex = QPersistentModelIndex(_visualItemsTree.
indexForObject(&_rallyGroupNode));
1298 _transformGroupIndex = QPersistentModelIndex(_visualItemsTree.
indexForObject(&_transformGroupNode));
1305void MissionController::_syncTreeMissionItemsInserted(
const QModelIndex& parent,
int first,
int last)
1308 for (
int i = first; i <= last; i++) {
1311 _visualItemsTree.
insertItem(i, item, _missionGroupIndex, QStringLiteral(
"missionItem"));
1316void MissionController::_syncTreeMissionItemsAboutToBeRemoved(
const QModelIndex& parent,
int first,
int last)
1320 for (
int i = last; i >= first; i--) {
1321 _visualItemsTree.
removeAt(_missionGroupIndex, i);
1325void MissionController::_syncTreeMissionItemsReset(
void)
1332 for (
int i = 0; i < _visualItems->
count(); i++) {
1335 _visualItemsTree.
appendItem(item, _missionGroupIndex, QStringLiteral(
"missionItem"));
1345void MissionController::_syncTreeRallyPointsInserted(
const QModelIndex& parent,
int first,
int last)
1349 if (!rallyController)
return;
1352 if (first == 0 && _visualItemsTree.
rowCount(_rallyGroupIndex) == 1) {
1353 const QModelIndex child = _visualItemsTree.
index(0, 0, _rallyGroupIndex);
1359 auto* pts = rallyController->points();
1360 for (
int i = first; i <= last; i++) {
1361 _visualItemsTree.
insertItem(i, (*pts)[i], _rallyGroupIndex, QStringLiteral(
"rallyItem"));
1365void MissionController::_syncTreeRallyPointsAboutToBeRemoved(
const QModelIndex& parent,
int first,
int last)
1368 for (
int i = last; i >= first; i--) {
1369 _visualItemsTree.
removeAt(_rallyGroupIndex, i);
1373void MissionController::_syncTreeRallyPointsRemoved(
const QModelIndex& parent,
int first,
int last)
1381 if (rallyController && rallyController->points()->count() == 0) {
1382 _rallyHeaderMarker.setObjectName(QStringLiteral(
"rallyHeader"));
1383 _visualItemsTree.
appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral(
"rallyHeader"));
1387void MissionController::_syncTreeRallyPointsReset(
void)
1395 if (rallyController && rallyController->points()->count() > 0) {
1396 auto* pts = rallyController->
points();
1397 for (
int i = 0; i < pts->count(); i++) {
1398 _visualItemsTree.
appendItem((*pts)[i], _rallyGroupIndex, QStringLiteral(
"rallyItem"));
1401 _rallyHeaderMarker.setObjectName(QStringLiteral(
"rallyHeader"));
1402 _visualItemsTree.
appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral(
"rallyHeader"));
1406void MissionController::_setPlannedHomePositionFromFirstCoordinate(
const QGeoCoordinate& clickCoordinate)
1408 bool foundFirstCoordinate =
false;
1409 QGeoCoordinate firstCoordinate;
1416 for (
int i=1; i<_visualItems->
count(); i++) {
1420 foundFirstCoordinate =
true;
1427 if (!foundFirstCoordinate) {
1428 firstCoordinate = clickCoordinate;
1431 if (firstCoordinate.isValid()) {
1432 QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
1433 plannedHomeCoord.setAltitude(0);
1438void MissionController::_recalcAllWithCoordinate(
const QGeoCoordinate& coordinate)
1441 _setPlannedHomePositionFromFirstCoordinate(coordinate);
1444 _recalcChildItems();
1449void MissionController::_recalcAll(
void)
1451 QGeoCoordinate emptyCoord;
1452 _recalcAllWithCoordinate(emptyCoord);
1456void MissionController::_initAllVisualItems(
void)
1460 if (!_settingsItem) {
1461 _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->
get(0));
1462 if (!_settingsItem) {
1463 qWarning() <<
"First item not MissionSettingsItem";
1472 for (
int i=0; i<_visualItems->
count(); i++) {
1474 _initVisualItem(item);
1478 _takeoffMissionItem = takeoffItem;
1488 connect(_visualItems, &QAbstractItemModel::rowsInserted,
this, &MissionController::_syncTreeMissionItemsInserted);
1489 connect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_syncTreeMissionItemsAboutToBeRemoved);
1490 connect(_visualItems, &QAbstractItemModel::modelReset,
this, &MissionController::_syncTreeMissionItemsReset);
1493 _syncTreeMissionItemsReset();
1497 if (rallyController) {
1498 auto* pts = rallyController->
points();
1499 connect(pts, &QAbstractItemModel::rowsInserted,
this, &MissionController::_syncTreeRallyPointsInserted);
1500 connect(pts, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_syncTreeRallyPointsAboutToBeRemoved);
1501 connect(pts, &QAbstractItemModel::rowsRemoved,
this, &MissionController::_syncTreeRallyPointsRemoved);
1502 connect(pts, &QAbstractItemModel::modelReset,
this, &MissionController::_syncTreeRallyPointsReset);
1505 _syncTreeRallyPointsReset();
1520void MissionController::_deinitAllVisualItems(
void)
1526 for (
int i=0; i<_visualItems->
count(); i++) {
1527 _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->
get(i)));
1534 disconnect(_visualItems, &QAbstractItemModel::rowsInserted,
this, &MissionController::_syncTreeMissionItemsInserted);
1535 disconnect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_syncTreeMissionItemsAboutToBeRemoved);
1536 disconnect(_visualItems, &QAbstractItemModel::modelReset,
this, &MissionController::_syncTreeMissionItemsReset);
1540 if (rallyController) {
1541 auto* pts = rallyController->
points();
1542 disconnect(pts, &QAbstractItemModel::rowsInserted,
this, &MissionController::_syncTreeRallyPointsInserted);
1543 disconnect(pts, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_syncTreeRallyPointsAboutToBeRemoved);
1544 disconnect(pts, &QAbstractItemModel::rowsRemoved,
this, &MissionController::_syncTreeRallyPointsRemoved);
1545 disconnect(pts, &QAbstractItemModel::modelReset,
this, &MissionController::_syncTreeRallyPointsReset);
1569 qWarning() <<
"isSimpleItem == true, yet not SimpleMissionItem";
1580 qWarning() <<
"ComplexMissionItem not found";
1590 disconnect(visualItem,
nullptr,
this,
nullptr);
1593void MissionController::_itemCommandChanged(
void)
1595 _recalcChildItems();
1599void MissionController::_managerVehicleChanged(
Vehicle* managerVehicle)
1601 if (_managerVehicle) {
1602 _missionManager->disconnect(
this);
1603 _managerVehicle->disconnect(
this);
1604 _managerVehicle =
nullptr;
1605 _missionManager =
nullptr;
1608 _managerVehicle = managerVehicle;
1609 if (!_managerVehicle) {
1610 qWarning() <<
"MissionController::managerVehicleChanged managerVehicle=NULL";
1632void MissionController::_inProgressChanged(
bool inProgress)
1640 double foundAltitude = 0;
1643 if (newIndex > _visualItems->
count()) {
1648 for (
int i=newIndex; i>0; i--) {
1665 *prevAltitude = foundAltitude;
1666 *prevAltitudeMode = foundAltFrame;
1672double MissionController::_normalizeLat(
double lat)
1678double MissionController::_normalizeLon(
double lon)
1687 qCDebug(MissionControllerLog) <<
"_addMissionSettings";
1693 _settingsItem = settingsItem;
1696 return settingsItem;
1702 int resumeIndex = 0;
1726 return currentIndex;
1730void MissionController::_currentMissionIndexChanged(
int sequenceNumber)
1737 for (
int i=0; i<_visualItems->
count(); i++) {
1752 return _visualItems ? _visualItems->
dirty() :
false;
1771 while (scanIndex < visualItems->count()) {
1774 qCDebug(MissionControllerLog) <<
"MissionController::_scanForAdditionalSettings count:scanIndex" <<
visualItems->
count() << scanIndex;
1798 return _visualItems ? _visualItems->
count() > 1 :
false;
1804 qCCritical(MissionControllerLog) <<
"MissionControllerLog::removeAllFromVehicle called while offline";
1806 qCCritical(MissionControllerLog) <<
"MissionControllerLog::removeAllFromVehicle called while syncInProgress";
1808 _itemsRequested =
true;
1828 if (_settingsItem) {
1831 return QGeoCoordinate();
1837 return _settingsItem && _settingsItem->
coordinate().isValid();
1842 if (_settingsItem) {
1849 double defaultAltitude = _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();
1851 for (
int i=1; i<_visualItems->
count(); i++) {
1857void MissionController::_progressPctChanged(
double progressPct)
1865void MissionController::_visualItemsDirtyChanged(
bool dirty)
1873 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle _flyView" <<
_flyView;
1875 qCCritical(MissionControllerLog) <<
"MissionController::showPlanFromManagerVehicle called while offline";
1880 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
1884 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle: syncInProgress wait for signal";
1888 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle: sync complete simulate signal";
1889 _itemsRequested =
true;
1890 _newMissionItemsAvailableFromVehicle(
false );
1896void MissionController::_managerSendComplete(
bool error)
1904void MissionController::_managerRemoveAllComplete(
bool error)
1914 return simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
1915 simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
1916 (simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI &&
1922 return simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI_NONE ||
1923 (simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI &&
1929 if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
1930 qCDebug(MissionControllerLog) <<
"setCurrentPlanViewSeqNum";
1931 bool foundLand =
false;
1932 int takeoffSeqNum = -1;
1933 int landSeqNum = -1;
1934 int lastFlyThroughSeqNum = -1;
1936 _splitSegment =
nullptr;
1937 _currentPlanViewItem =
nullptr;
1938 _currentPlanViewSeqNum = -1;
1939 _currentPlanViewVIIndex = -1;
1940 _onlyInsertTakeoffValid =
false;
1941 _isInsertTakeoffValid =
true;
1942 _isInsertLandValid =
true;
1943 _isROIActive =
false;
1944 _isROIBeginCurrentItem =
false;
1945 _flyThroughCommandsAllowed =
true;
1946 _previousCoordinate = QGeoCoordinate();
1948 bool noItemsAddedYet = _visualItems->
count() == 1;
1950 _onlyInsertTakeoffValid =
true;
1953 for (
int viIndex=0; viIndex<_visualItems->
count(); viIndex++) {
1958 if (sequenceNumber != 0 && currentSeqNumber <= sequenceNumber) {
1961 _isInsertTakeoffValid =
false;
1965 if (qobject_cast<TakeoffMissionItem*>(pVI)) {
1966 takeoffSeqNum = currentSeqNumber;
1967 _isInsertTakeoffValid =
false;
1973 case MAV_CMD_NAV_LAND:
1974 case MAV_CMD_NAV_VTOL_LAND:
1975 case MAV_CMD_DO_LAND_START:
1976 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1978 landSeqNum = currentSeqNumber;
1987 landSeqNum = currentSeqNumber;
1994 if (currentSeqNumber < sequenceNumber && simpleItem->specifiesCoordinate() && !simpleItem->
isStandaloneCoordinate()) {
1995 _previousCoordinate = simpleItem->
coordinate();
1999 if (currentSeqNumber <= sequenceNumber) {
2001 if (_isROICancelItem(simpleItem)) {
2002 _isROIActive =
false;
2005 if (_isROIBeginItem(simpleItem)) {
2006 _isROIActive =
true;
2010 if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
2011 _isROIBeginCurrentItem =
true;
2018 lastFlyThroughSeqNum = currentSeqNumber;
2022 if (currentSeqNumber == sequenceNumber) {
2026 _currentPlanViewItem = pVI;
2027 _currentPlanViewSeqNum = sequenceNumber;
2028 _currentPlanViewVIIndex = viIndex;
2033 for (
int j=viIndex-1; j>0; j--) {
2037 if (_flightPathSegmentHashTable.contains(splitPair)) {
2038 _splitSegment = _flightPathSegmentHashTable[splitPair];
2042 _delayedSplitSegmentUpdate =
true;
2058 if (takeoffSeqNum != -1) {
2060 if (sequenceNumber < takeoffSeqNum) {
2062 _isInsertLandValid =
false;
2064 _flyThroughCommandsAllowed =
false;
2068 if (lastFlyThroughSeqNum != -1) {
2070 if (sequenceNumber < lastFlyThroughSeqNum) {
2071 _isInsertLandValid =
false;
2076 _isInsertLandValid =
false;
2077 if (sequenceNumber >= landSeqNum) {
2079 _flyThroughCommandsAllowed =
false;
2083 if (_hasLandItem != foundLand) {
2085 _hasLandItem = foundLand;
2090 _isInsertLandValid = _isInsertLandValid && !_onlyInsertTakeoffValid;
2091 _flyThroughCommandsAllowed = _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid;
2103 bool repositionTakeoffItems,
2104 bool repositionLandingItems)
2106 if (!newHome.isValid()) {
2107 qCWarning(MissionControllerLog) <<
"Cannot reposition mission to an invalid coordinate";
2111 if (!_settingsItem || !_settingsItem->
coordinate().isValid()) {
2112 qCWarning(MissionControllerLog) <<
"Cannot reposition mission while home is invalid";
2116 const QGeoCoordinate oldHome = _settingsItem->
coordinate();
2118 for (
int i = 0; i < _visualItems->
count(); ++i) {
2119 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2129 const QGeoCoordinate oldCoord = item->
coordinate();
2130 if (!oldCoord.isValid()) {
2134 const double distanceMeters = oldHome.distanceTo(oldCoord);
2135 const double azimuthDegrees = oldHome.azimuthTo(oldCoord);
2137 QGeoCoordinate newCoord = newHome.atDistanceAndAzimuth(distanceMeters, azimuthDegrees);
2147 bool offsetTakeoffItems,
2148 bool offsetLandingItems)
2150 if (!qFuzzyIsNull(eastMeters) || !qFuzzyIsNull(northMeters)) {
2151 const double distanceMeters = qSqrt(eastMeters * eastMeters + northMeters * northMeters);
2152 double azimuthDegrees = 0.0;
2153 if (!qFuzzyIsNull(distanceMeters)) {
2154 const double azimuthRadians = qAtan2(eastMeters, northMeters);
2155 azimuthDegrees = qRadiansToDegrees(azimuthRadians);
2158 for (
int i = 0; i < _visualItems->
count(); ++i) {
2159 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2169 const QGeoCoordinate oldCoord = item->
coordinate();
2170 if (!oldCoord.isValid()) {
2174 item->
setCoordinate(oldCoord.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
2180 if (!qFuzzyIsNull(upMeters)) {
2181 for (
int i = 0; i < _visualItems->
count(); ++i) {
2182 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2183 if (!item || item == _settingsItem) {
2206 bool rotateTakeoffItems,
2207 bool rotateLandingItems)
2209 if (qFuzzyIsNull(degreesCW)) {
2213 if (!_settingsItem || !_settingsItem->
coordinate().isValid()) {
2214 qCWarning(MissionControllerLog) <<
"Cannot rotate mission while home is invalid";
2218 const QGeoCoordinate home = _settingsItem->
coordinate();
2220 for (
int i = 0; i < _visualItems->
count(); ++i) {
2221 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2231 const QGeoCoordinate oldCoord = item->
coordinate();
2232 if (!oldCoord.isValid()) {
2236 const double distanceMeters = home.distanceTo(oldCoord);
2237 if (qFuzzyIsNull(distanceMeters)) {
2240 const double azimuthDegrees = home.azimuthTo(oldCoord);
2242 QGeoCoordinate newCoord = home.atDistanceAndAzimuth(distanceMeters, azimuthDegrees + degreesCW);
2249void MissionController::_updateTimeout()
2251 QGeoCoordinate firstCoordinate;
2255 double south = 180.0;
2257 double west = 360.0;
2260 for (
int i = 1; i < _visualItems->
count(); i++) {
2265 switch(pSimpleItem->
command()) {
2266 case MAV_CMD_NAV_TAKEOFF:
2267 case MAV_CMD_NAV_WAYPOINT:
2268 case MAV_CMD_NAV_LAND:
2274 if((MAV_CMD)pSimpleItem->
command() == MAV_CMD_NAV_TAKEOFF) {
2277 minAlt = maxAlt = alt;
2278 }
else if(!firstCoordinate.isValid()) {
2281 double lat = pSimpleItem->
coordinate().latitude() + 90.0;
2282 double lon = pSimpleItem->
coordinate().longitude() + 180.0;
2283 north = fmax(north, lat);
2284 south = fmin(south, lat);
2285 east = fmax(east, lon);
2286 west = fmin(west, lon);
2287 minAlt = fmin(minAlt, alt);
2288 maxAlt = fmax(maxAlt, alt);
2300 if(!firstCoordinate.isValid() && pComplexItem->
entryCoordinate().isValid()) {
2303 north = fmax(north, bc.
pointNW.latitude() + 90.0);
2304 south = fmin(south, bc.
pointSE.latitude() + 90.0);
2305 east = fmax(east, bc.
pointNW.longitude() + 180.0);
2306 west = fmin(west, bc.
pointSE.longitude() + 180.0);
2307 minAlt = fmin(minAlt, bc.
pointNW.altitude());
2308 maxAlt = fmax(maxAlt, bc.
pointSE.altitude());
2315 if(firstCoordinate.isValid()) {
2323 QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
2324 QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2325 if(_travelBoundingCube != boundingCube || _takeoffCoordinate !=
takeoffCoordinate) {
2327 _travelBoundingCube = boundingCube;
2329 qCDebug(MissionControllerLog) <<
"Bounding cube:" << _travelBoundingCube.
pointNW << _travelBoundingCube.
pointSE;
2333void MissionController::_complexBoundingBoxChanged()
2339 const int count = _visualItems->
count();
2341 for (
int i = 0; i < count; i++) {
2342 QObject *obj = _visualItems->
get(i);
2346 return landingItem == item;
2355 return _visualItems->
count() <= 1;
2358void MissionController::_forceRecalcOfAllowedBits(
void)
2364void MissionController::_allItemsRemoved(
void)
2371void MissionController::_firstItemAdded(
void)
2394 return _globalAltFrame;
2402 return _globalAltFrame;
2408 if (_globalAltFrame != altFrame) {
2409 _globalAltFrame = altFrame;
#define UPDATE_TIMEOUT
How often we check for bounding box changes.
QPair< VisualMissionItem *, VisualMissionItem * > VisualItemPair
QHash< VisualItemPair, FlightPathSegment * > FlightPathSegmentHashTable
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void setSpecifyCameraMode(bool specifyCameraMode)
void setSpecifyGimbal(bool specifyGimbal)
bool specifyCameraMode(void) const
bool cameraModeSupported(void) const
bool specifyGimbal(void) const
void isIncompleteChanged(void)
void boundingCubeChanged(void)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
void greatestDistanceToChanged(void)
bool isIncomplete(void) const
virtual void applyPreviousAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame prevAltFrame, double prevAltitude)
void maxAMSLAltitudeChanged(void)
virtual bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString)=0
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLinkTypes::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual bool sendHomePositionToVehicle() const
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
static constexpr const char * canonicalName
void terrainCollisionChanged(bool terrainCollision)
void totalDistanceChanged(double totalDistance)
void setCoordinate2(const QGeoCoordinate &coordinate)
void coord2AMSLAltChanged(void)
@ SegmentTypeTerrainFrame
void coord1AMSLAltChanged(void)
void setSpecialVisual(bool specialVisual)
void amslTerrainHeightsChanged(void)
void setCoord2AMSLAlt(double alt)
void setCoord1AMSLAlt(double alt)
void setCoordinate1(const QGeoCoordinate &coordinate)
Used to convert a Plan to a KML document.
void addMission(Vehicle *vehicle, QmlObjectListModel *visualItems, QList< MissionItem * > rgMissionItems)
static MissionCommandTree * instance()
void minAMSLAltitudeChanged(double minAMSLAltitude)
Q_INVOKABLE void resumeMission(int resumeIndex)
double progressPct(void) const
Q_INVOKABLE int visualItemIndexForObject(QObject *object) const
Returns the visual item index for the given VisualMissionItem object, or -1 if not found.
void complexMissionItemsChanged(void)
Q_INVOKABLE void setHomePosition(QGeoCoordinate coordinate)
Set the planned home position from a map click.
bool showPlanFromManagerVehicle(void) final
Q_INVOKABLE SendToVehiclePreCheckState sendToVehiclePreCheck(void)
bool dirty(void) const final
Q_INVOKABLE VisualMissionItem * insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem=false)
void batteriesRequiredChanged(int batteriesRequired)
bool loadTextFile(QFile &file, QString &errorString)
void multipleLandPatternsAllowedChanged(void)
bool multipleLandPatternsAllowed(void) const
Q_INVOKABLE VisualMissionItem * insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
QGeoCoordinate takeoffCoordinate()
Q_INVOKABLE VisualMissionItem * insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
Q_INVOKABLE void offsetMission(double eastMeters, double northMeters, double upMeters=0.0, bool offsetTakeoffItems=false, bool offsetLandingItems=false)
Q_INVOKABLE void setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
void maxAMSLAltitudeChanged(double maxAMSLAltitude)
void removeAllFromVehicle(void) final
void homePositionSetChanged(void)
void recalcTerrainProfile(void)
void missionPlannedDistanceChanged(double missionPlannedDistance)
void missionTotalDistanceChanged(double missionTotalDistance)
void hasLandItemChanged(void)
void _recalcFlightPathSegmentsSignal(void)
int currentMissionIndex(void) const
void missionMaxTelemetryChanged(double missionMaxTelemetry)
static void sendItemsToVehicle(Vehicle *vehicle, QmlObjectListModel *visualMissionItems)
Sends the mission items to the specified vehicle.
bool load(const QJsonObject &json, QString &errorString) final
void splitSegmentChanged(void)
Q_INVOKABLE void repositionMission(const QGeoCoordinate &newHome, bool repositionTakeoffItems=true, bool repositionLandingItems=true)
void resumeMissionReady(void)
SendToVehiclePreCheckState
@ SendToVehiclePreCheckStateFirwmareVehicleMismatch
@ SendToVehiclePreCheckStateNoActiveVehicle
@ SendToVehiclePreCheckStateOk
@ SendToVehiclePreCheckStateActiveMission
void batteryChangePointChanged(int batteryChangePoint)
Q_INVOKABLE void rotateMission(double degreesCW, bool rotateTakeoffItems=false, bool rotateLandingItems=false)
void addMissionToKML(KMLPlanDomDocument &planKML)
void _recalcMissionFlightStatusSignal(void)
void missionHoverDistanceChanged(double missionHoverDistance)
bool syncInProgress(void) const final
void sendToVehicle(void) final
void resumeMissionIndexChanged(void)
void currentMissionIndexChanged(int currentMissionIndex)
Q_INVOKABLE VisualMissionItem * insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
Q_INVOKABLE void removeVisualItem(int viIndex)
void newItemsFromVehicle(void)
void setGlobalAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame altFrame)
void save(QJsonObject &json) final
Q_INVOKABLE VisualMissionItem * insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void missionHoverTimeChanged(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
QGeoCoordinate plannedHomePosition(void) const
bool homePositionSet(void) const
bool containsItems(void) const final
void progressPctChanged(double progressPct)
void missionCruiseTimeChanged(void)
QGroundControlQmlGlobal::AltitudeFrame globalAltitudeFrame(void)
int readyForSaveState(void) const
QGroundControlQmlGlobal::AltitudeFrame globalAltitudeFrameDefault(void)
void removeAll(void) final
Removes all from controller only.
void visualItemsReset(void)
void missionBoundingCubeChanged(void)
QVariantList complexMissionItems(void) const
void missionTimeChanged(void)
Q_INVOKABLE void applyDefaultMissionAltitude(void)
Updates the altitudes of the items in the current mission to the new default altitude.
void setDirty(bool dirty) final
void start(bool flyView) final
Should be called immediately upon Component.onCompleted.
void planViewStateChanged(void)
All plan-view properties are recomputed together in setCurrentPlanViewSeqNum, so one signal covers th...
void globalAltitudeFrameChanged(void)
void missionCruiseDistanceChanged(double missionCruiseDistance)
void resumeMissionUploadFail(void)
void loadFromVehicle(void) final
Q_INVOKABLE VisualMissionItem * insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem=false)
int resumeMissionIndex(void) const
Q_INVOKABLE VisualMissionItem * insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectListModel * visualItems(void)
void reset(Vehicle *controllerVehicle, Vehicle *managerVehicle, bool missionContainsVTOLTakeoff)
Resets the flight status fields to defaults based on vehicle properties.
double maxAMSLAltitude() const
const MissionFlightStatus_t & status() const
double minAMSLAltitude() const
void recalc(QmlObjectListModel *visualItems, MissionSettingsItem *settingsItem, Vehicle *controllerVehicle, Vehicle *managerVehicle, AppSettings *appSettings, PlanViewSettings *planViewSettings, bool missionContainsVTOLTakeoff)
void setParam1(double param1)
MAV_FRAME frame(void) const
void save(QJsonObject &json) const
double param1(void) const
QGeoCoordinate coordinate(void) const
int lastCurrentIndex(void) const
Last current mission item reported while in Mission flight mode.
void generateResumeMission(int resumeIndex)
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
bool scanForMissionSettings(QmlObjectListModel *visualItems, int scanIndex)
Scans the loaded items for settings items.
QGeoCoordinate coordinate(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
bool addMissionEndAction(QList< MissionItem * > &items, int seqNum, QObject *missionItemParent)
CameraSection * cameraSection(void)
void endResetModel()
Depth-counted endResetModel — only the outermost call has effect.
void beginResetModel()
Depth-counted beginResetModel — only the outermost call has effect.
void dirtyChanged(bool dirty)
void countChanged(int count)
This is the abstract base clas for Plan Element controllers.
void syncInProgressChanged(bool syncInProgress)
PlanMasterController * masterController(void)
PlanMasterController * _masterController
virtual void start(bool flyView)
Should be called immediately upon Component.onCompleted.
void containsItemsChanged()
void dirtyChanged(bool dirty)
void resumeMissionUploadFail(void)
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void sendComplete(bool error)
void resumeMissionReady(void)
void newMissionItemsAvailable(bool removeAllRequested)
void loadFromVehicle(void)
void removeAllComplete(bool error)
void writeMissionItems(const QList< MissionItem * > &missionItems)
bool inProgress(void) const
void inProgressChanged(bool inProgress)
void progressPctChanged(double progressPercentPct)
const QList< MissionItem * > & missionItems(void)
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
void managerVehicleChanged(Vehicle *managerVehicle)
RallyPointController * rallyPointController(void)
Vehicle * managerVehicle(void)
virtual ComplexMissionItem * createComplexMissionItem(const QString &complexItemType, PlanMasterController *masterController, bool flyView, const QString &kmlOrShpFile=QString())
virtual QVariantList complexMissionItemNames(Vehicle *vehicle)
static QGCCorePlugin * instance()
Q_INVOKABLE bool isValid() const
static VehicleClass_t vehicleClass(MAV_TYPE mavType)
static MAV_TYPE vehicleClassToMavType(VehicleClass_t vehicleClass)
static FirmwareClass_t firmwareClass(MAV_AUTOPILOT autopilot)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
void setDirty(bool dirty) override final
Q_INVOKABLE QObject * get(int index)
QObject * removeAt(int index)
int count() const override final
void clear() override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
void insert(int index, QObject *object)
int indexOf(const QObject *object)
int rowCount(const QModelIndex &parent=QModelIndex()) const override
static constexpr int NodeTypeRole
QVariant data(const QModelIndex &index, int role=Qt::DisplayRole) const override
void removeChildren(const QModelIndex &parentIndex)
Removes all children of parentIndex without removing the parent itself.
Q_INVOKABLE QObject * removeItem(const QModelIndex &index)
QObject * removeAt(const QModelIndex &parentIndex, int row)
QModelIndex index(int row, int column, const QModelIndex &parent=QModelIndex()) const override
Q_INVOKABLE QModelIndex indexForObject(QObject *object) const
Searches the entire tree for object and returns its QModelIndex (invalid if not found)
Q_INVOKABLE QModelIndex insertItem(int row, QObject *object, const QModelIndex &parentIndex=QModelIndex())
Inserts object at row under parentIndex. Returns the new item's index.
Q_INVOKABLE QModelIndex appendItem(QObject *object, const QModelIndex &parentIndex=QModelIndex())
Appends object as the last child of parentIndex (root if invalid). Returns the new item's index.
QmlObjectListModel * points(void)
Provides access to all app settings.
static SettingsManager * instance()
AppSettings * appSettings() const
A SimpleMissionItem is used to represent a single MissionItem to the ui.
bool specifiesCoordinate(void) const final
void setSequenceNumber(int sequenceNumber) final
bool isStandaloneCoordinate(void) const final
int sequenceNumber(void) const final
bool scanForSections(QmlObjectListModel *visualItems, int scanIndex, PlanMasterController *masterController)
int lastSequenceNumber(void) const final
MAV_CMD mavCommand(void) const
bool specifiesAltitude(void) const
QGeoCoordinate coordinate(void) const final
virtual bool load(QTextStream &loadStream)
void setCoordinate(const QGeoCoordinate &coordinate) override
void setCommand(int command)
void setAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame altitudeFrame)
MissionItem & missionItem(void)
QGroundControlQmlGlobal::AltitudeFrame altitudeFrame(void) const
Takeoff mission item is a special case of a SimpleMissionItem which supports Launch Location display/...
static bool isTakeoffCommand(MAV_CMD command)
bool load(QTextStream &loadStream) final
static constexpr const char * canonicalName
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
bool takeoffMissionCommand() const
void defaultHoverSpeedChanged(double hoverSpeed)
void defaultCruiseSpeedChanged(double cruiseSpeed)
QString missionFlightMode() const
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
QString flightMode() const
MAV_TYPE vehicleType() const
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
bool isOfflineEditingVehicle() const
MAV_AUTOPILOT firmwareType() const
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
void trackFirmwareVehicleTypeChanges(void)
double defaultHoverSpeed() const
void stopTrackingFirmwareVehicleTypeChanges(void)
bool initialPlanRequestComplete() const
double defaultCruiseSpeed() const
VehicleSupports * supports()
MissionManager * missionManager()
void vehicleTypeChanged()
virtual int lastSequenceNumber(void) const =0
void setIsCurrentItem(bool isCurrentItem)
void setHasCurrentChildItem(bool hasCurrentChildItem)
void specifiedVehicleYawChanged(void)
virtual void setCoordinate(const QGeoCoordinate &coordinate)=0
virtual int sequenceNumber(void) const =0
virtual void applyNewAltitude(double newAltitude)=0
Adjust the altitude of the item if appropriate to the new altitude.
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
virtual bool isTakeoffItem(void) const
virtual bool isStandaloneCoordinate(void) const =0
void amslExitAltChanged(double alt)
void setParentItem(VisualMissionItem *parentItem)
void terrainAltitudeChanged(double terrainAltitude)
void setWizardMode(bool wizardMode)
bool isCurrentItem(void) const
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void specifiesCoordinateChanged(void)
void coordinateChanged(const QGeoCoordinate &coordinate)
void setSimpleFlighPathSegment(FlightPathSegment *segment)
void specifiedFlightSpeedChanged(void)
void clearSimpleFlighPathSegment(void)
void currentVTOLModeChanged(void)
Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
virtual void setSequenceNumber(int sequenceNumber)=0
virtual ReadyForSaveState readyForSaveState(void) const
void specifiedGimbalYawChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
virtual QGeoCoordinate coordinate(void) const =0
virtual bool specifiesAltitudeOnly(void) const =0
virtual void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)=0
virtual QString commandName(void) const =0
virtual bool isLandCommand(void) const
static constexpr const char * jsonTypeSimpleItemValue
Item type is MISSION_ITEM.
virtual QGCGeoBoundingCube * boundingCube(void)
virtual bool isSimpleItem(void) const =0
QmlObjectListModel * childItems(void)
virtual bool specifiesCoordinate(void) const =0
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void additionalTimeDelayChanged(void)
virtual void save(QJsonArray &missionItems)=0
VisualMissionItem * parentItem(void)
virtual QGeoCoordinate entryCoordinate(void) const =0
virtual double editableAlt(void) const =0
bool loadGeoCoordinate(const QJsonValue &jsonValue, bool altitudeRequired, QGeoCoordinate &coordinate, QString &errorString)
void saveGeoCoordinate(const QGeoCoordinate &coordinate, bool writeAltitude, QJsonValue &jsonValue)
Saves a QGeoCoordinate as [lat, lon, alt] array (QGC plan format).
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
int batteriesRequired
-1 for not supported
double maxTelemetryDistance
int batteryChangePoint
-1 for not supported, 0 for not needed
static constexpr VehicleClass_t VehicleClassGeneric