28#include <QtCore/QJsonArray>
29#include <QtCore/QJsonDocument>
32#define UPDATE_TIMEOUT 5000
38 , _controllerVehicle (masterController->controllerVehicle())
39 , _managerVehicle (masterController->managerVehicle())
40 , _missionManager (masterController->managerVehicle()->missionManager())
45 _resetMissionFlightStatus();
47 _updateTimer.setSingleShot(
true);
49 connect(&_updateTimer, &QTimer::timeout,
this, &MissionController::_updateTimeout);
50 connect(_planViewSettings->takeoffItemNotRequired(), &
Fact::rawValueChanged,
this, &MissionController::_forceRecalcOfAllowedBits);
69void MissionController::_resetMissionFlightStatus(
void)
98 _missionFlightStatus.
ampMinutesAvailable =
static_cast<double>(_missionFlightStatus.
mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
115 qCDebug(MissionControllerLog) <<
"start flyView" << flyView;
117 _managerVehicleChanged(_managerVehicle);
124void MissionController::_init(
void)
127 _addMissionSettings(_visualItems);
132 _initAllVisualItems();
136void MissionController::_newMissionItemsAvailableFromVehicle(
bool removeAllRequested)
138 qCDebug(MissionControllerLog) <<
"_newMissionItemsAvailableFromVehicle flyView:count" <<
_flyView << _missionManager->
missionItems().count();
152 _deinitAllVisualItems();
154 _visualItems->deleteLater();
155 _visualItems =
nullptr;
156 _settingsItem =
nullptr;
157 _takeoffMissionItem =
nullptr;
158 _updateContainsItems();
161 const QList<MissionItem*>& newMissionItems = _missionManager->
missionItems();
162 qCDebug(MissionControllerLog) <<
"loading from vehicle: count"<< newMissionItems.count();
164 _missionItemCount = newMissionItems.count();
173 if (fakeHomeItem->
coordinate().latitude() != 0 || fakeHomeItem->
coordinate().longitude() != 0) {
179 bool weHaveItemsFromVehicle =
false;
180 for (; i < newMissionItems.count(); i++) {
181 weHaveItemsFromVehicle =
true;
182 const MissionItem* missionItem = newMissionItems[i];
188 simpleItem->deleteLater();
189 simpleItem = _takeoffMissionItem;
191 newControllerMissionItems->
append(simpleItem);
194 _visualItems = newControllerMissionItems;
195 _settingsItem = settingsItem;
202 _initAllVisualItems();
203 _updateContainsItems();
206 _itemsRequested =
false;
212 qCCritical(MissionControllerLog) <<
"MissionControllerLog::loadFromVehicle called while offline";
214 qCCritical(MissionControllerLog) <<
"MissionControllerLog::loadFromVehicle called while syncInProgress";
216 _itemsRequested =
true;
224 qCCritical(MissionControllerLog) <<
"MissionControllerLog::sendToVehicle called while offline";
226 qCCritical(MissionControllerLog) <<
"MissionControllerLog::sendToVehicle called while syncInProgress";
228 qCDebug(MissionControllerLog) <<
"MissionControllerLog::sendToVehicle";
229 if (_visualItems->
count() == 1) {
243bool MissionController::_convertToMissionItems(
QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
245 if (visualMissionItems->
count() == 0) {
249 bool endActionSet =
false;
252 for (
int i=0; i<visualMissionItems->
count(); i++) {
258 qCDebug(MissionControllerLog) <<
"_convertToMissionItems seqNum:lastSeqNum:command"
267 endActionSet = settingsItem->
addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
275 QObject* deleteParent =
new QObject();
276 QList<MissionItem*> rgMissionItems;
278 _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
279 planKML.
addMission(_controllerVehicle, _visualItems, rgMissionItems);
280 deleteParent->deleteLater();
286 QList<MissionItem*> rgMissionItems;
288 _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
295int MissionController::_nextSequenceNumber(
void)
297 if (_visualItems->
count() == 0) {
298 qWarning() <<
"Internal error: Empty visual item list";
306VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command,
int visualItemIndex,
bool makeCurrentItem)
308 int sequenceNumber = _nextSequenceNumber();
313 _initVisualItem(newItem);
320 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltMode)) {
321 newItem->
altitude()->setRawValue(prevAltitude);
329 if (visualItemIndex == -1) {
330 _visualItems->
append(newItem);
332 _visualItems->
insert(visualItemIndex, newItem);
336 _recalcAllWithCoordinate(coordinate);
338 if (makeCurrentItem) {
350 return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_WAYPOINT, visualItemIndex, makeCurrentItem);
355 int sequenceNumber = _nextSequenceNumber();
358 _initVisualItem(_takeoffMissionItem);
364 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltMode)) {
365 _takeoffMissionItem->
altitude()->setRawValue(prevAltitude);
369 if (visualItemIndex == -1) {
370 _visualItems->
append(_takeoffMissionItem);
372 _visualItems->
insert(visualItemIndex, _takeoffMissionItem);
377 if (makeCurrentItem) {
383 return _takeoffMissionItem;
390 ->rawValue().toBool() &&
399 }
else if (_controllerVehicle->
vtol()) {
403 return _insertSimpleMissionItemWorker(coordinate, _controllerVehicle->
vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
409 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));
415 _recalcROISpecialVisuals();
421 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE, visualItemIndex, makeCurrentItem));
427 _recalcROISpecialVisuals();
443 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltMode)) {
444 qobject_cast<SurveyComplexItem*>(newItem)->cameraCalc()->setDistanceMode(prevAltMode);
456 qWarning() <<
"Internal error: Unknown complex item:" << itemName;
460 _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
476 qWarning() <<
"Internal error: Unknown complex item:" << itemName;
480 _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
485void MissionController::_insertComplexMissionItemWorker(
const QGeoCoordinate& mapCenterCoordinate,
ComplexMissionItem* complexItem,
int visualItemIndex,
bool makeCurrentItem)
487 int sequenceNumber = _nextSequenceNumber();
488 bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
489 qobject_cast<CorridorScanComplexItem*>(complexItem) ||
490 qobject_cast<StructureScanComplexItem*>(complexItem);
492 if (surveyStyleItem) {
493 bool rollSupported =
false;
494 bool pitchSupported =
false;
495 bool yawSupported =
false;
503 if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
505 cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
509 if (_controllerVehicle->
firmwarePlugin()->
hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
511 if (!cameraSection->specifyGimbal()) {
512 cameraSection->setSpecifyGimbal(
true);
513 cameraSection->gimbalPitch()->setRawValue(-90.0);
519 if (!qobject_cast<VTOLLandingComplexItem*>(complexItem)) {
522 _initVisualItem(complexItem);
524 if (visualItemIndex == -1) {
525 _visualItems->
append(complexItem);
527 _visualItems->
insert(visualItemIndex, complexItem);
534 _recalcAllWithCoordinate(mapCenterCoordinate);
536 if (makeCurrentItem) {
544 return _visualItems ? _visualItems->
indexOf(
object) : -1;
547void MissionController::removeVisualItem(
int viIndex)
549 if (viIndex <= 0 || viIndex >= _visualItems->
count()) {
550 qWarning() <<
"MissionController::removeVisualItem called with bad index - count:index" << _visualItems->
count() << viIndex;
557 if (item == _takeoffMissionItem) {
558 _takeoffMissionItem =
nullptr;
561 _deinitVisualItem(item);
564 if (removeSurveyStyle) {
566 bool foundSurvey =
false;
567 for (
int i=1; i<_visualItems->
count(); i++) {
576 bool rollSupported =
false;
577 bool pitchSupported =
false;
578 bool yawSupported =
false;
580 if (_controllerVehicle->
firmwarePlugin()->
hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
581 if (cameraSection->specifyGimbal() && cameraSection->
gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->
gimbalYaw()->rawValue().toDouble() == 0.0) {
595 if (viIndex >= _visualItems->
count()) {
596 newVIIndex = _visualItems->
count() - 1;
598 newVIIndex = viIndex;
604 if (_visualItems->
count() == 1) {
612 _deinitAllVisualItems();
614 _visualItems->deleteLater();
615 _settingsItem =
nullptr;
616 _takeoffMissionItem =
nullptr;
618 _addMissionSettings(_visualItems);
619 _initAllVisualItems();
621 _resetMissionFlightStatus();
629 QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
630 { _jsonPlannedHomePositionKey, QJsonValue::Object,
true },
631 { _jsonItemsKey, QJsonValue::Array,
true },
632 { _jsonMavAutopilotKey, QJsonValue::Double,
false },
633 { _jsonComplexItemsKey, QJsonValue::Array,
true },
642 QList<SurveyComplexItem*> surveyItems;
643 QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
644 qCDebug(MissionControllerLog) <<
"Json load: complex item count" << complexArray.count();
645 for (
int i=0; i<complexArray.count(); i++) {
646 const QJsonValue& itemValue = complexArray[i];
648 if (!itemValue.isObject()) {
649 errorString = QStringLiteral(
"Mission item is not an object");
654 const QJsonObject itemObject = itemValue.toObject();
656 surveyItems.append(item);
664 int nextSimpleItemIndex= 0;
665 int nextComplexItemIndex= 0;
666 int nextSequenceNumber = 1;
667 QJsonArray itemArray(json[_jsonItemsKey].toArray());
670 if (json.contains(_jsonPlannedHomePositionKey)) {
672 if (item->
load(json[_jsonPlannedHomePositionKey].toObject(), 0,
errorString)) {
680 qCDebug(MissionControllerLog) <<
"Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
682 qCDebug(MissionControllerLog) <<
"Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;
685 if (nextComplexItemIndex < surveyItems.count()) {
689 qCDebug(MissionControllerLog) <<
"Json load: injecting complex item expectedSequence:actualSequence:" << nextSequenceNumber << complexItem->
sequenceNumber();
692 nextComplexItemIndex++;
698 if (nextSimpleItemIndex < itemArray.count()) {
699 const QJsonValue& itemValue = itemArray[nextSimpleItemIndex++];
701 if (!itemValue.isObject()) {
702 errorString = QStringLiteral(
"Mission item is not an object");
706 const QJsonObject itemObject = itemValue.toObject();
716 qCDebug(MissionControllerLog) <<
"Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->
sequenceNumber();
723 }
while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
731 QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
732 { _jsonPlannedHomePositionKey, QJsonValue::Array,
true },
733 { _jsonItemsKey, QJsonValue::Array,
true },
734 { _jsonFirmwareTypeKey, QJsonValue::Double,
true },
735 { _jsonVehicleTypeKey, QJsonValue::Double,
false },
736 { _jsonCruiseSpeedKey, QJsonValue::Double,
false },
737 { _jsonHoverSpeedKey, QJsonValue::Double,
false },
738 { _jsonGlobalPlanAltitudeModeKey, QJsonValue::Double,
false },
746 qCDebug(MissionControllerLog) <<
"MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
748 AppSettings* appSettings = SettingsManager::instance()->appSettings();
751 MAV_AUTOPILOT planFileFirmwareType =
static_cast<MAV_AUTOPILOT
>(json[_jsonFirmwareTypeKey].toInt());
753 if (json.contains(_jsonVehicleTypeKey)) {
754 planFileVehicleType =
static_cast<MAV_TYPE
>(json[_jsonVehicleTypeKey].toInt());
760 if (json.contains(_jsonVehicleTypeKey)) {
770 if (json.contains(_jsonCruiseSpeedKey)) {
773 if (json.contains(_jsonHoverSpeedKey)) {
776 if (json.contains(_jsonGlobalPlanAltitudeModeKey)) {
777 setGlobalAltitudeMode(json[_jsonGlobalPlanAltitudeModeKey].toVariant().value<QGroundControlQmlGlobal::AltMode>());
780 QGeoCoordinate homeCoordinate;
787 qCDebug(MissionControllerLog) <<
"plannedHomePosition" << homeCoordinate;
791 int nextSequenceNumber = 1;
792 const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
793 for (
int i=0; i<rgMissionItems.count(); i++) {
795 const QJsonValue& itemValue = rgMissionItems[i];
796 if (!itemValue.isObject()) {
797 errorString = tr(
"Mission item %1 is not an object").arg(i);
800 const QJsonObject itemObject = itemValue.toObject();
804 QList<JsonHelper::KeyValidateInfo> itemKeyInfoList = {
819 simpleItem->deleteLater();
820 simpleItem = takeoffItem;
822 qCDebug(MissionControllerLog) <<
"Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->
command();
829 QList<JsonHelper::KeyValidateInfo> complexItemKeyInfoList = {
838 qCDebug(MissionControllerLog) <<
"Loading Survey: nextSequenceNumber" << nextSequenceNumber;
840 if (!surveyItem->
load(itemObject, nextSequenceNumber++,
errorString)) {
844 qCDebug(MissionControllerLog) <<
"Survey load complete: nextSequenceNumber" << nextSequenceNumber;
847 qCDebug(MissionControllerLog) <<
"Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
849 if (!landingItem->
load(itemObject, nextSequenceNumber++,
errorString)) {
853 qCDebug(MissionControllerLog) <<
"FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
856 qCDebug(MissionControllerLog) <<
"Loading VTOL Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
858 if (!landingItem->
load(itemObject, nextSequenceNumber++,
errorString)) {
862 qCDebug(MissionControllerLog) <<
"VTOL Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
865 qCDebug(MissionControllerLog) <<
"Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
867 if (!structureItem->
load(itemObject, nextSequenceNumber++,
errorString)) {
871 qCDebug(MissionControllerLog) <<
"Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
874 qCDebug(MissionControllerLog) <<
"Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
876 if (!corridorItem->
load(itemObject, nextSequenceNumber++,
errorString)) {
880 qCDebug(MissionControllerLog) <<
"Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
883 errorString = tr(
"Unsupported complex item type: %1").arg(complexItemType);
886 errorString = tr(
"Unknown item type: %1").arg(itemType);
895 if (doJumpItem->
command() == MAV_CMD_DO_JUMP) {
909 errorString = tr(
"Could not find doJumpId: %1").arg(findDoJumpId);
934 bool firstItem =
true;
935 bool plannedHomePositionInFile =
false;
937 QString firstLine = stream.readLine();
938 const QStringList& version = firstLine.split(
" ");
940 bool versionOk =
false;
941 if (version.size() == 3 && version[0] ==
"QGC" && version[1] ==
"WPL") {
942 if (version[2] ==
"110") {
945 plannedHomePositionInFile =
true;
946 }
else if (version[2] ==
"120") {
949 plannedHomePositionInFile =
false;
956 while (!stream.atEnd()) {
958 if (item->
load(stream)) {
959 if (firstItem && plannedHomePositionInFile) {
972 errorString = tr(
"The mission file is corrupted.");
977 errorString = tr(
"The mission file is not compatible with this version of %1.").arg(QCoreApplication::applicationName());
981 if (!plannedHomePositionInFile) {
985 if (item && item->
command() == MAV_CMD_DO_JUMP) {
997 _deinitAllVisualItems();
998 _visualItems->deleteLater();
1000 _settingsItem =
nullptr;
1001 _takeoffMissionItem =
nullptr;
1003 _visualItems = loadedVisualItems;
1005 if (_visualItems->
count() == 0) {
1006 _addMissionSettings(_visualItems);
1013 _initAllVisualItems();
1015 if (_visualItems->
count() > 1) {
1025 QString errorMessage = tr(
"Mission: %1");
1028 if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
1032 _initLoadedVisualItems(loadedVisualItems);
1040 QString errorMessage = tr(
"Mission: %1");
1041 QByteArray bytes = file.readAll();
1042 QTextStream stream(bytes);
1047 if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1052 _initLoadedVisualItems(loadedVisualItems);
1059 for (
int i=0; i<_visualItems->
count(); i++) {
1076 if (!settingsItem) {
1077 qWarning() <<
"First item is not MissionSettingsItem";
1080 QJsonValue coordinateValue;
1082 json[_jsonPlannedHomePositionKey] = coordinateValue;
1083 json[_jsonFirmwareTypeKey] = _controllerVehicle->
firmwareType();
1084 json[_jsonVehicleTypeKey] = _controllerVehicle->
vehicleType();
1087 json[_jsonGlobalPlanAltitudeModeKey] = _globalAltMode;
1091 QJsonArray rgJsonMissionItems;
1092 for (
int i=0; i<_visualItems->
count(); i++) {
1095 visualItem->
save(rgJsonMissionItems);
1100 QList<MissionItem*> rgMissionItems;
1102 if (_convertToMissionItems(_visualItems, rgMissionItems,
this )) {
1103 QJsonObject saveObject;
1104 MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
1105 missionItem->
save(saveObject);
1106 rgJsonMissionItems.append(saveObject);
1108 for (
int i=0; i<rgMissionItems.count(); i++) {
1109 rgMissionItems[i]->deleteLater();
1113 json[_jsonItemsKey] = rgJsonMissionItems;
1116void MissionController::_calcPrevWaypointValues(
VisualMissionItem* currentItem,
VisualMissionItem* prevItem,
double* azimuth,
double* distance,
double* altDifference)
1124 *distance = prevCoord.distanceTo(currentCoord);
1125 *azimuth = prevCoord.azimuthTo(currentCoord);
1132 bool distanceOk =
false;
1136 return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1143 bool takeoffStraightUp = pair.second->isTakeoffItem() && !_controllerVehicle->
fixedWing();
1145 QGeoCoordinate coord1 = pair.first->exitCoordinate();
1146 QGeoCoordinate coord2 = pair.second->entryCoordinate();
1147 double coord2AMSLAlt = pair.second->amslEntryAlt();
1148 double coord1AMSLAlt = takeoffStraightUp ? coord2AMSLAlt : pair.first->amslExitAlt();
1151 if (pair.second->isTakeoffItem()) {
1153 }
else if (pair.second->isLandCommand()) {
1159 if (takeoffStraightUp) {
1186 _flightPathSegmentHashTable[pair] = segment = prevItemPairHashTable.take(pair);
1188 segment = _createFlightPathSegmentWorker(pair, mavlinkTerrainFrame);
1189 _flightPathSegmentHashTable[pair] = segment;
1192 _simpleFlightPathSegments.
append(segment);
1197void MissionController::_recalcROISpecialVisuals(
void)
1200 VisualMissionItem* lastCoordinateItem = qobject_cast<VisualMissionItem*>(_visualItems->
get(0));
1201 bool roiActive =
false;
1203 for (
int i=1; i<_visualItems->
count(); i++) {
1210 if (_isROICancelItem(simpleItem)) {
1214 if (_isROIBeginItem(simpleItem)) {
1222 if (_flightPathSegmentHashTable.contains(viPair)) {
1223 _flightPathSegmentHashTable[viPair]->setSpecialVisual(roiActive);
1225 lastCoordinateItem = visualItem;
1230void MissionController::_recalcFlightPathSegments(
void)
1233 int segmentCount = 0;
1234 bool firstCoordinateNotFound =
true;
1236 bool linkEndToHome =
false;
1237 bool linkStartToHome = _controllerVehicle->
rover() ? true :
false;
1238 bool foundRTL =
false;
1239 bool homePositionValid = _settingsItem->
coordinate().isValid();
1240 bool roiActive =
false;
1241 bool previousItemIsIncomplete =
false;
1242 bool signalSplitSegmentChanged =
false;
1244 qCDebug(MissionControllerLog) <<
"_recalcFlightPathSegments homePositionValid" << homePositionValid;
1248 _missionContainsVTOLTakeoff =
false;
1249 _flightPathSegmentHashTable.clear();
1254 _simpleFlightPathSegments.
clear();
1255 _directionArrows.
clear();
1262 for (
int i=1; i<_visualItems->
count(); i++) {
1263 qobject_cast<VisualMissionItem*>(_visualItems->
get(i))->clearSimpleFlighPathSegment();
1267 for (
int i=1; i<_visualItems->
count(); i++) {
1276 if (_isROICancelItem(simpleItem)) {
1280 if (_isROIBeginItem(simpleItem)) {
1287 case MAV_CMD_NAV_TAKEOFF:
1288 case MAV_CMD_NAV_VTOL_TAKEOFF:
1289 _missionContainsVTOLTakeoff = command == MAV_CMD_NAV_VTOL_TAKEOFF;
1290 if (!linkEndToHome) {
1293 if (firstCoordinateNotFound) {
1294 linkStartToHome =
true;
1298 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1299 linkEndToHome =
true;
1314 lastFlyThroughVI = visualItem;
1324 previousItemIsIncomplete =
true;
1325 }
else if (previousItemIsIncomplete) {
1327 previousItemIsIncomplete =
false;
1328 firstCoordinateNotFound =
false;
1329 lastFlyThroughVI = visualItem;
1331 if (lastFlyThroughVI != _settingsItem || (homePositionValid && linkStartToHome)) {
1332 bool addDirectionArrow =
false;
1338 addDirectionArrow =
true;
1339 }
else if (segmentCount > 5) {
1341 addDirectionArrow =
true;
1346 lastSegmentVisualItemPair =
VisualItemPair(lastFlyThroughVI, visualItem);
1347 SimpleMissionItem* lastSimpleItem = qobject_cast<SimpleMissionItem*>(lastFlyThroughVI);
1348 bool mavlinkTerrainFrame = lastSimpleItem ? lastSimpleItem->
missionItem().
frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT :
false;
1349 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair, mavlinkTerrainFrame);
1351 if (addDirectionArrow) {
1352 _directionArrows.
append(segment);
1354 if (visualItem->
isCurrentItem() && _delayedSplitSegmentUpdate) {
1355 _splitSegment = segment;
1356 _delayedSplitSegmentUpdate =
false;
1357 signalSplitSegmentChanged =
true;
1361 firstCoordinateNotFound =
false;
1362 lastFlyThroughVI = visualItem;
1367 if (linkEndToHome && lastFlyThroughVI != _settingsItem && homePositionValid) {
1368 lastSegmentVisualItemPair =
VisualItemPair(lastFlyThroughVI, _settingsItem);
1369 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair,
false );
1375 if (lastSegmentVisualItemPair.first) {
1381 if (_flightPathSegmentHashTable.contains(lastSegmentVisualItemPair)) {
1383 coordVector = _flightPathSegmentHashTable[lastSegmentVisualItemPair];
1384 }
else if (oldSegmentTable.contains(lastSegmentVisualItemPair)) {
1386 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector = oldSegmentTable.take(lastSegmentVisualItemPair);
1391 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->entryCoordinate() : lastSegmentVisualItemPair.first->exitCoordinate(),
1392 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->amslEntryAlt() : lastSegmentVisualItemPair.first->amslExitAlt(),
1393 lastSegmentVisualItemPair.second->entryCoordinate(),
1394 lastSegmentVisualItemPair.second->amslEntryAlt(),
1397 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector;
1400 _directionArrows.
append(coordVector);
1407 qDeleteAll(oldSegmentTable);
1412 if (signalSplitSegmentChanged) {
1417void MissionController::_updateBatteryInfo(
int waypointIndex)
1432void MissionController::_addHoverTime(
double hoverTime,
double hoverDistance,
int waypointIndex)
1434 _missionFlightStatus.
totalTime += hoverTime;
1435 _missionFlightStatus.
hoverTime += hoverTime;
1438 _updateBatteryInfo(waypointIndex);
1441void MissionController::_addCruiseTime(
double cruiseTime,
double cruiseDistance,
int waypointIndex)
1443 _missionFlightStatus.
totalTime += cruiseTime;
1444 _missionFlightStatus.
cruiseTime += cruiseTime;
1447 _updateBatteryInfo(waypointIndex);
1456void MissionController::_addTimeDistance(
bool vtolInHover,
double hoverTime,
double cruiseTime,
double extraTime,
double distance,
int seqNum)
1458 if (_controllerVehicle->
vtol()) {
1460 _addHoverTime(hoverTime, distance, seqNum);
1461 _addHoverTime(extraTime, 0, -1);
1463 _addCruiseTime(cruiseTime, distance, seqNum);
1464 _addCruiseTime(extraTime, 0, -1);
1468 _addHoverTime(hoverTime, distance, seqNum);
1469 _addHoverTime(extraTime, 0, -1);
1471 _addCruiseTime(cruiseTime, distance, seqNum);
1472 _addCruiseTime(extraTime, 0, -1);
1477void MissionController::_recalcMissionFlightStatus()
1479 if (!_visualItems->
count()) {
1483 bool firstCoordinateItem =
true;
1486 bool homePositionValid = _settingsItem->
coordinate().isValid();
1488 qCDebug(MissionControllerLog) <<
"_recalcMissionFlightStatus";
1500 _minAMSLAltitude = _maxAMSLAltitude = qQNaN();
1502 _resetMissionFlightStatus();
1504 bool linkStartToHome =
false;
1505 bool foundRTL =
false;
1506 bool pastLandCommand =
false;
1507 double totalHorizontalDistance = 0;
1509 for (
int i=0; i<_visualItems->
count(); i++) {
1514 if (simpleItem && simpleItem->
mavCommand() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
1527 switch (simpleItem->
command()) {
1528 case MAV_CMD_NAV_ROI:
1529 case MAV_CMD_DO_SET_ROI_LOCATION:
1530 case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
1531 case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
1532 _missionFlightStatus.
gimbalYaw = qQNaN();
1543 _missionFlightStatus.
gimbalYaw = gimbalYaw;
1553 if (i != 0 && !foundRTL) {
1559 if (firstCoordinateItem && simpleItem && (simpleItem->
mavCommand() == MAV_CMD_NAV_TAKEOFF || simpleItem->
mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1560 if (homePositionValid) {
1561 linkStartToHome =
true;
1562 if (_controllerVehicle->
multiRotor() || _controllerVehicle->
vtol()) {
1564 double azimuth, distance, altDifference;
1565 _calcPrevWaypointValues(_settingsItem, simpleItem, &azimuth, &distance, &altDifference);
1567 _addHoverTime(takeoffTime, 0, -1);
1572 if (!pastLandCommand)
1580 _minAMSLAltitude = std::fmin(_minAMSLAltitude, amslAltitude);
1581 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, amslAltitude);
1586 _minAMSLAltitude = std::fmin(_minAMSLAltitude, complexMinAMSLAltitude);
1587 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, complexMaxAMSLAltitude);
1591 firstCoordinateItem =
false;
1596 if (qIsNaN(newVehicleYaw)) {
1598 if (simpleItem != lastFlyThroughVI) {
1602 _missionFlightStatus.
vehicleYaw = newVehicleYaw;
1607 if (lastFlyThroughVI != _settingsItem || linkStartToHome) {
1609 double azimuth, distance, altDifference;
1611 _calcPrevWaypointValues(item, lastFlyThroughVI, &azimuth, &distance, &altDifference);
1615 totalHorizontalDistance += distance;
1618 if (!pastLandCommand) {
1620 double hoverTime = distance / _missionFlightStatus.
hoverSpeed;
1621 double cruiseTime = distance / _missionFlightStatus.
cruiseSpeed;
1638 if (!pastLandCommand) {
1639 double hoverTime = distance / _missionFlightStatus.
hoverSpeed;
1640 double cruiseTime = distance / _missionFlightStatus.
cruiseSpeed;
1644 totalHorizontalDistance += distance;
1648 lastFlyThroughVI = item;
1656 if (!qIsNaN(newSpeed)) {
1659 }
else if (_controllerVehicle->
vtol()) {
1672 if (simpleItem && _controllerVehicle->
vtol()) {
1673 switch (simpleItem->
command()) {
1674 case MAV_CMD_NAV_TAKEOFF:
1675 case MAV_CMD_NAV_VTOL_TAKEOFF:
1676 case MAV_CMD_NAV_LAND:
1679 case MAV_CMD_NAV_VTOL_LAND:
1682 case MAV_CMD_DO_VTOL_TRANSITION:
1685 if (transitionState == MAV_VTOL_STATE_MC) {
1687 }
else if (transitionState == MAV_VTOL_STATE_FW) {
1698 pastLandCommand =
true;
1704 if (foundRTL && lastFlyThroughVI != _settingsItem && homePositionValid) {
1705 double azimuth, distance, altDifference;
1706 _calcPrevWaypointValues(lastFlyThroughVI, _settingsItem, &azimuth, &distance, &altDifference);
1708 if (!pastLandCommand) {
1710 double hoverTime = distance / _missionFlightStatus.
hoverSpeed;
1711 double cruiseTime = distance / _missionFlightStatus.
cruiseSpeed;
1717 _missionFlightStatus.
totalDistance = totalHorizontalDistance;
1723 if (linkStartToHome) {
1725 _minAMSLAltitude = std::fmin(_minAMSLAltitude, _settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
1726 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, _settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
1743 double altRange = _maxAMSLAltitude - _minAMSLAltitude;
1744 for (
int i=0; i<_visualItems->
count(); i++) {
1749 if (altRange == 0.0) {
1754 item->
setAltPercent((amslAlt - _minAMSLAltitude) / altRange);
1756 if (qIsNaN(terrainAltitude)) {
1773void MissionController::_recalcSequence(
void)
1775 if (_inRecalcSequence) {
1782 _inRecalcSequence =
true;
1783 int sequenceNumber = 0;
1784 for (
int i=0; i<_visualItems->
count(); i++) {
1789 _inRecalcSequence =
false;
1793void MissionController::_recalcChildItems(
void)
1799 for (
int i=1; i<_visualItems->
count(); i++) {
1808 currentParentItem = item;
1819void MissionController::_setupTreeModel(
void)
1823 _visualItemsTree.
clear();
1826 _planFileGroupNode.setObjectName(tr(
"Plan File"));
1827 _planFileGroupIndex = QPersistentModelIndex(
1828 _visualItemsTree.
appendItem(&_planFileGroupNode, QModelIndex(), QStringLiteral(
"planFileGroup")));
1830 _planFileInfoMarker.setObjectName(QStringLiteral(
"planFileInfo"));
1831 _visualItemsTree.
appendItem(&_planFileInfoMarker, _planFileGroupIndex, QStringLiteral(
"planFileInfo"));
1834 _defaultsGroupNode.setObjectName(tr(
"Defaults"));
1835 _defaultsGroupIndex = QPersistentModelIndex(
1836 _visualItemsTree.
appendItem(&_defaultsGroupNode, QModelIndex(), QStringLiteral(
"defaultsGroup")));
1838 _defaultsInfoMarker.setObjectName(QStringLiteral(
"defaultsInfo"));
1839 _visualItemsTree.
appendItem(&_defaultsInfoMarker, _defaultsGroupIndex, QStringLiteral(
"defaultsInfo"));
1842 _missionItemsGroupNode.setObjectName(tr(
"Mission Items"));
1843 _missionGroupIndex = QPersistentModelIndex(
1844 _visualItemsTree.
appendItem(&_missionItemsGroupNode, QModelIndex(), QStringLiteral(
"missionGroup")));
1847 _fenceGroupNode.setObjectName(tr(
"GeoFence"));
1848 _fenceGroupIndex = QPersistentModelIndex(
1849 _visualItemsTree.
appendItem(&_fenceGroupNode, QModelIndex(), QStringLiteral(
"fenceGroup")));
1852 _fenceEditorMarker.setObjectName(QStringLiteral(
"fenceEditor"));
1853 _visualItemsTree.
appendItem(&_fenceEditorMarker, _fenceGroupIndex, QStringLiteral(
"fenceEditor"));
1856 _rallyGroupNode.setObjectName(tr(
"Rally Points"));
1857 _rallyGroupIndex = QPersistentModelIndex(
1858 _visualItemsTree.
appendItem(&_rallyGroupNode, QModelIndex(), QStringLiteral(
"rallyGroup")));
1861 _rallyHeaderMarker.setObjectName(QStringLiteral(
"rallyHeader"));
1862 _visualItemsTree.
appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral(
"rallyHeader"));
1869void MissionController::_onMissionItemsInserted(
const QModelIndex& parent,
int first,
int last)
1872 for (
int i = first; i <= last; i++) {
1875 _visualItemsTree.
insertItem(i, item, _missionGroupIndex, QStringLiteral(
"missionItem"));
1880void MissionController::_onMissionItemsAboutToBeRemoved(
const QModelIndex& parent,
int first,
int last)
1884 for (
int i = last; i >= first; i--) {
1885 _visualItemsTree.
removeAt(_missionGroupIndex, i);
1889void MissionController::_onMissionItemsReset(
void)
1895 for (
int i = 0; i < _visualItems->
count(); i++) {
1898 _visualItemsTree.
appendItem(item, _missionGroupIndex, QStringLiteral(
"missionItem"));
1908void MissionController::_onRallyPointsInserted(
const QModelIndex& parent,
int first,
int last)
1912 if (!rallyController)
return;
1915 if (first == 0 && _visualItemsTree.
rowCount(_rallyGroupIndex) == 1) {
1916 const QModelIndex child = _visualItemsTree.
index(0, 0, _rallyGroupIndex);
1922 auto* pts = rallyController->points();
1923 for (
int i = first; i <= last; i++) {
1924 _visualItemsTree.
insertItem(i, (*pts)[i], _rallyGroupIndex, QStringLiteral(
"rallyItem"));
1928void MissionController::_onRallyPointsAboutToBeRemoved(
const QModelIndex& parent,
int first,
int last)
1931 for (
int i = last; i >= first; i--) {
1932 _visualItemsTree.
removeAt(_rallyGroupIndex, i);
1937 if (rallyController && (rallyController->points()->count() - (last - first + 1)) == 0) {
1938 _rallyHeaderMarker.setObjectName(QStringLiteral(
"rallyHeader"));
1939 _visualItemsTree.
appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral(
"rallyHeader"));
1943void MissionController::_onRallyPointsReset(
void)
1950 if (rallyController && rallyController->points()->count() > 0) {
1951 auto* pts = rallyController->
points();
1952 for (
int i = 0; i < pts->count(); i++) {
1953 _visualItemsTree.
appendItem((*pts)[i], _rallyGroupIndex, QStringLiteral(
"rallyItem"));
1956 _rallyHeaderMarker.setObjectName(QStringLiteral(
"rallyHeader"));
1957 _visualItemsTree.
appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral(
"rallyHeader"));
1961void MissionController::_setPlannedHomePositionFromFirstCoordinate(
const QGeoCoordinate& clickCoordinate)
1963 bool foundFirstCoordinate =
false;
1964 QGeoCoordinate firstCoordinate;
1971 for (
int i=1; i<_visualItems->
count(); i++) {
1975 foundFirstCoordinate =
true;
1982 if (!foundFirstCoordinate) {
1983 firstCoordinate = clickCoordinate;
1986 if (firstCoordinate.isValid()) {
1987 QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
1988 plannedHomeCoord.setAltitude(0);
1993void MissionController::_recalcAllWithCoordinate(
const QGeoCoordinate& coordinate)
1996 _setPlannedHomePositionFromFirstCoordinate(coordinate);
1999 _recalcChildItems();
2004void MissionController::_recalcAll(
void)
2006 QGeoCoordinate emptyCoord;
2007 _recalcAllWithCoordinate(emptyCoord);
2011void MissionController::_initAllVisualItems(
void)
2015 if (!_settingsItem) {
2016 _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->
get(0));
2017 if (!_settingsItem) {
2018 qWarning() <<
"First item not MissionSettingsItem";
2026 for (
int i=0; i<_visualItems->
count(); i++) {
2028 _initVisualItem(item);
2032 _takeoffMissionItem = takeoffItem;
2042 connect(_visualItems, &QAbstractItemModel::rowsInserted,
this, &MissionController::_onMissionItemsInserted);
2043 connect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_onMissionItemsAboutToBeRemoved);
2044 connect(_visualItems, &QAbstractItemModel::modelReset,
this, &MissionController::_onMissionItemsReset);
2047 _onMissionItemsReset();
2051 if (rallyController) {
2052 auto* pts = rallyController->
points();
2053 connect(pts, &QAbstractItemModel::rowsInserted,
this, &MissionController::_onRallyPointsInserted);
2054 connect(pts, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_onRallyPointsAboutToBeRemoved);
2055 connect(pts, &QAbstractItemModel::modelReset,
this, &MissionController::_onRallyPointsReset);
2058 _onRallyPointsReset();
2072void MissionController::_deinitAllVisualItems(
void)
2077 for (
int i=0; i<_visualItems->
count(); i++) {
2078 _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->
get(i)));
2085 disconnect(_visualItems, &QAbstractItemModel::rowsInserted,
this, &MissionController::_onMissionItemsInserted);
2086 disconnect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_onMissionItemsAboutToBeRemoved);
2087 disconnect(_visualItems, &QAbstractItemModel::modelReset,
this, &MissionController::_onMissionItemsReset);
2091 if (rallyController) {
2092 auto* pts = rallyController->
points();
2093 disconnect(pts, &QAbstractItemModel::rowsInserted,
this, &MissionController::_onRallyPointsInserted);
2094 disconnect(pts, &QAbstractItemModel::rowsAboutToBeRemoved,
this, &MissionController::_onRallyPointsAboutToBeRemoved);
2095 disconnect(pts, &QAbstractItemModel::modelReset,
this, &MissionController::_onRallyPointsReset);
2119 qWarning() <<
"isSimpleItem == true, yet not SimpleMissionItem";
2130 qWarning() <<
"ComplexMissionItem not found";
2140 disconnect(visualItem,
nullptr,
this,
nullptr);
2143void MissionController::_itemCommandChanged(
void)
2145 _recalcChildItems();
2149void MissionController::_managerVehicleChanged(
Vehicle* managerVehicle)
2151 if (_managerVehicle) {
2152 _missionManager->disconnect(
this);
2153 _managerVehicle->disconnect(
this);
2154 _managerVehicle =
nullptr;
2155 _missionManager =
nullptr;
2158 _managerVehicle = managerVehicle;
2159 if (!_managerVehicle) {
2160 qWarning() <<
"MissionController::managerVehicleChanged managerVehicle=NULL";
2182void MissionController::_inProgressChanged(
bool inProgress)
2190 double foundAltitude = 0;
2193 if (newIndex > _visualItems->
count()) {
2198 for (
int i=newIndex; i>0; i--) {
2205 foundAltitude = simpleItem->
altitude()->rawValue().toDouble();
2215 *prevAltitude = foundAltitude;
2216 *prevAltitudeMode = foundAltMode;
2222double MissionController::_normalizeLat(
double lat)
2228double MissionController::_normalizeLon(
double lon)
2237 qCDebug(MissionControllerLog) <<
"_addMissionSettings";
2243 _settingsItem = settingsItem;
2246 return settingsItem;
2249void MissionController::_centerHomePositionOnMissionItems(
QmlObjectListModel *visualItems)
2251 qCDebug(MissionControllerLog) <<
"_centerHomePositionOnMissionItems";
2258 bool firstCoordSet =
false;
2263 if (firstCoordSet) {
2266 north = fmax(north, lat);
2267 south = fmin(south, lat);
2268 east = fmax(east, lon);
2269 west = fmin(west, lon);
2271 firstCoordSet =
true;
2280 if (firstCoordSet) {
2281 _settingsItem->
setInitialHomePositionFromUser(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
2289 int resumeIndex = 0;
2313 return currentIndex;
2317void MissionController::_currentMissionIndexChanged(
int sequenceNumber)
2324 for (
int i=0; i<_visualItems->
count(); i++) {
2339 return _visualItems ? _visualItems->dirty() :
false;
2358 while (scanIndex < visualItems->count()) {
2361 qCDebug(MissionControllerLog) <<
"MissionController::_scanForAdditionalSettings count:scanIndex" <<
visualItems->
count() << scanIndex;
2383void MissionController::_updateContainsItems(
void)
2390 return _visualItems ? _visualItems->
count() > 1 :
false;
2396 qCCritical(MissionControllerLog) <<
"MissionControllerLog::removeAllFromVehicle called while offline";
2398 qCCritical(MissionControllerLog) <<
"MissionControllerLog::removeAllFromVehicle called while syncInProgress";
2400 _itemsRequested =
true;
2407 QStringList complexItems;
2411 if (_controllerVehicle->
multiRotor() || _controllerVehicle->
vtol()) {
2417 return QGCCorePlugin::instance()->complexMissionItemNames(_controllerVehicle, complexItems);
2430 if (_settingsItem) {
2433 return QGeoCoordinate();
2441 for (
int i=1; i<_visualItems->
count(); i++) {
2447void MissionController::_progressPctChanged(
double progressPct)
2455void MissionController::_visualItemsDirtyChanged(
bool dirty)
2463 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle _flyView" <<
_flyView;
2465 qCCritical(MissionControllerLog) <<
"MissionController::showPlanFromManagerVehicle called while offline";
2470 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
2474 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle: syncInProgress wait for signal";
2478 qCDebug(MissionControllerLog) <<
"showPlanFromManagerVehicle: sync complete simulate signal";
2479 _itemsRequested =
true;
2480 _newMissionItemsAvailableFromVehicle(
false );
2486void MissionController::_managerSendComplete(
bool error)
2494void MissionController::_managerRemoveAllComplete(
bool error)
2504 return simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
2505 simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
2506 (simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI &&
2512 return simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI_NONE ||
2513 (simpleItem->
mavCommand() == MAV_CMD_DO_SET_ROI &&
2519 if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
2520 qCDebug(MissionControllerLog) <<
"setCurrentPlanViewSeqNum";
2521 bool foundLand =
false;
2522 int takeoffSeqNum = -1;
2523 int landSeqNum = -1;
2524 int lastFlyThroughSeqNum = -1;
2526 _splitSegment =
nullptr;
2527 _currentPlanViewItem =
nullptr;
2528 _currentPlanViewSeqNum = -1;
2529 _currentPlanViewVIIndex = -1;
2530 _onlyInsertTakeoffValid =
false;
2531 _isInsertTakeoffValid =
true;
2532 _isInsertLandValid =
true;
2533 _isROIActive =
false;
2534 _isROIBeginCurrentItem =
false;
2535 _flyThroughCommandsAllowed =
true;
2536 _previousCoordinate = QGeoCoordinate();
2538 bool noItemsAddedYet = _visualItems->
count() == 1;
2540 _onlyInsertTakeoffValid =
true;
2543 for (
int viIndex=0; viIndex<_visualItems->
count(); viIndex++) {
2548 if (sequenceNumber != 0 && currentSeqNumber <= sequenceNumber) {
2551 _isInsertTakeoffValid =
false;
2555 if (qobject_cast<TakeoffMissionItem*>(pVI)) {
2556 takeoffSeqNum = currentSeqNumber;
2557 _isInsertTakeoffValid =
false;
2563 case MAV_CMD_NAV_LAND:
2564 case MAV_CMD_NAV_VTOL_LAND:
2565 case MAV_CMD_DO_LAND_START:
2566 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
2568 landSeqNum = currentSeqNumber;
2577 landSeqNum = currentSeqNumber;
2584 if (currentSeqNumber < sequenceNumber && simpleItem->specifiesCoordinate() && !simpleItem->
isStandaloneCoordinate()) {
2585 _previousCoordinate = simpleItem->
coordinate();
2589 if (currentSeqNumber <= sequenceNumber) {
2591 if (_isROICancelItem(simpleItem)) {
2592 _isROIActive =
false;
2595 if (_isROIBeginItem(simpleItem)) {
2596 _isROIActive =
true;
2600 if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
2601 _isROIBeginCurrentItem =
true;
2608 lastFlyThroughSeqNum = currentSeqNumber;
2612 if (currentSeqNumber == sequenceNumber) {
2616 _currentPlanViewItem = pVI;
2617 _currentPlanViewSeqNum = sequenceNumber;
2618 _currentPlanViewVIIndex = viIndex;
2623 for (
int j=viIndex-1; j>0; j--) {
2627 if (_flightPathSegmentHashTable.contains(splitPair)) {
2628 _splitSegment = _flightPathSegmentHashTable[splitPair];
2632 _delayedSplitSegmentUpdate =
true;
2648 if (takeoffSeqNum != -1) {
2650 if (sequenceNumber < takeoffSeqNum) {
2652 _isInsertLandValid =
false;
2654 _flyThroughCommandsAllowed =
false;
2658 if (lastFlyThroughSeqNum != -1) {
2660 if (sequenceNumber < lastFlyThroughSeqNum) {
2661 _isInsertLandValid =
false;
2666 _isInsertLandValid =
false;
2667 if (sequenceNumber >= landSeqNum) {
2669 _flyThroughCommandsAllowed =
false;
2673 if (_hasLandItem != foundLand) {
2675 _hasLandItem = foundLand;
2680 _isInsertLandValid = _isInsertLandValid && !_onlyInsertTakeoffValid;
2681 _flyThroughCommandsAllowed = _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid;
2698 bool repositionTakeoffItems,
2699 bool repositionLandingItems)
2701 if (!newHome.isValid()) {
2702 qCWarning(MissionControllerLog) <<
"Cannot reposition mission to an invalid coordinate";
2706 if (!_settingsItem || !_settingsItem->
coordinate().isValid()) {
2707 qCWarning(MissionControllerLog) <<
"Cannot reposition mission while home is invalid";
2711 const QGeoCoordinate oldHome = _settingsItem->
coordinate();
2713 for (
int i = 0; i < _visualItems->
count(); ++i) {
2714 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2724 const QGeoCoordinate oldCoord = item->
coordinate();
2725 if (!oldCoord.isValid()) {
2729 const double distanceMeters = oldHome.distanceTo(oldCoord);
2730 const double azimuthDegrees = oldHome.azimuthTo(oldCoord);
2732 QGeoCoordinate newCoord = newHome.atDistanceAndAzimuth(distanceMeters, azimuthDegrees);
2742 bool offsetTakeoffItems,
2743 bool offsetLandingItems)
2745 if (!_settingsItem || !_settingsItem->
coordinate().isValid()) {
2746 qCWarning(MissionControllerLog) <<
"Cannot offset mission while home is invalid";
2750 if (!qFuzzyIsNull(eastMeters) || !qFuzzyIsNull(northMeters)) {
2751 double distanceMeters = qSqrt(eastMeters * eastMeters + northMeters * northMeters);
2752 double azimuthDegrees = 0.0;
2753 if (!qFuzzyIsNull(distanceMeters)) {
2754 const double azimuthRadians = qAtan2(eastMeters, northMeters);
2755 azimuthDegrees = qRadiansToDegrees(azimuthRadians);
2758 const QGeoCoordinate oldHome = _settingsItem->
coordinate();
2759 QGeoCoordinate newHome = oldHome.atDistanceAndAzimuth(distanceMeters, azimuthDegrees);
2763 if (!qFuzzyIsNull(upMeters)) {
2764 for (
int i = 0; i < _visualItems->
count(); ++i) {
2765 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2766 if (!item || item == _settingsItem) {
2787 bool rotateTakeoffItems,
2788 bool rotateLandingItems)
2790 if (qFuzzyIsNull(degreesCW)) {
2794 if (!_settingsItem || !_settingsItem->
coordinate().isValid()) {
2795 qCWarning(MissionControllerLog) <<
"Cannot rotate mission while home is invalid";
2799 const QGeoCoordinate home = _settingsItem->
coordinate();
2801 for (
int i = 0; i < _visualItems->
count(); ++i) {
2802 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->
get(i));
2812 const QGeoCoordinate oldCoord = item->
coordinate();
2813 if (!oldCoord.isValid()) {
2817 const double distanceMeters = home.distanceTo(oldCoord);
2818 if (qFuzzyIsNull(distanceMeters)) {
2821 const double azimuthDegrees = home.azimuthTo(oldCoord);
2823 QGeoCoordinate newCoord = home.atDistanceAndAzimuth(distanceMeters, azimuthDegrees + degreesCW);
2830void MissionController::_updateTimeout()
2832 QGeoCoordinate firstCoordinate;
2836 double south = 180.0;
2838 double west = 360.0;
2841 for (
int i = 1; i < _visualItems->
count(); i++) {
2846 switch(pSimpleItem->
command()) {
2847 case MAV_CMD_NAV_TAKEOFF:
2848 case MAV_CMD_NAV_WAYPOINT:
2849 case MAV_CMD_NAV_LAND:
2852 if (!pSimpleItem->
altitude()->rawValue().isNull() && !qIsNaN(pSimpleItem->
altitude()->rawValue().toDouble())) {
2853 alt = pSimpleItem->
altitude()->rawValue().toDouble();
2855 if((MAV_CMD)pSimpleItem->
command() == MAV_CMD_NAV_TAKEOFF) {
2858 minAlt = maxAlt = alt;
2859 }
else if(!firstCoordinate.isValid()) {
2862 double lat = pSimpleItem->
coordinate().latitude() + 90.0;
2863 double lon = pSimpleItem->
coordinate().longitude() + 180.0;
2864 north = fmax(north, lat);
2865 south = fmin(south, lat);
2866 east = fmax(east, lon);
2867 west = fmin(west, lon);
2868 minAlt = fmin(minAlt, alt);
2869 maxAlt = fmax(maxAlt, alt);
2881 if(!firstCoordinate.isValid() && pComplexItem->
entryCoordinate().isValid()) {
2884 north = fmax(north, bc.
pointNW.latitude() + 90.0);
2885 south = fmin(south, bc.
pointSE.latitude() + 90.0);
2886 east = fmax(east, bc.
pointNW.longitude() + 180.0);
2887 west = fmin(west, bc.
pointSE.longitude() + 180.0);
2888 minAlt = fmin(minAlt, bc.
pointNW.altitude());
2889 maxAlt = fmax(maxAlt, bc.
pointSE.altitude());
2896 if(firstCoordinate.isValid()) {
2904 QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
2905 QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2906 if(_travelBoundingCube != boundingCube || _takeoffCoordinate !=
takeoffCoordinate) {
2908 _travelBoundingCube = boundingCube;
2910 qCDebug(MissionControllerLog) <<
"Bounding cube:" << _travelBoundingCube.
pointNW << _travelBoundingCube.
pointSE;
2914void MissionController::_complexBoundingBoxChanged()
2920 const int count = _visualItems->
count();
2922 for (
int i = 0; i < count; i++) {
2923 QObject *obj = _visualItems->
get(i);
2927 return landingItem == item;
2936 return _visualItems->
count() <= 1;
2939void MissionController::_forceRecalcOfAllowedBits(
void)
2960void MissionController::_allItemsRemoved(
void)
2967void MissionController::_firstItemAdded(
void)
2990 return _globalAltMode;
2998 return _globalAltMode;
3004 if (_globalAltMode != altMode) {
3005 _globalAltMode = altMode;
#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)
Fact *offlineEditingAscentSpeed READ offlineEditingAscentSpeed CONSTANT Fact * offlineEditingAscentSpeed()
Fact *offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT Fact * offlineEditingCruiseSpeed()
Fact *offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT Fact * offlineEditingHoverSpeed()
Fact *offlineEditingDescentSpeed READ offlineEditingDescentSpeed CONSTANT Fact * offlineEditingDescentSpeed()
Fact *offlineEditingFirmwareClass READ offlineEditingFirmwareClass CONSTANT Fact * offlineEditingFirmwareClass()
Fact *offlineEditingVehicleClass READ offlineEditingVehicleClass CONSTANT Fact * offlineEditingVehicleClass()
Fact *batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT Fact * batteryPercentRemainingAnnounce()
Fact *defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT Fact * defaultMissionItemAltitude()
void setSpecifyCameraMode(bool specifyCameraMode)
void setSpecifyGimbal(bool specifyGimbal)
bool specifyCameraMode(void) const
bool cameraModeSupported(void) const
void isIncompleteChanged(void)
void boundingCubeChanged(void)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
virtual double minAMSLAltitude(void) const =0
void greatestDistanceToChanged(void)
bool isIncomplete(void) const
virtual double greatestDistanceTo(const QGeoCoordinate &other) const =0
virtual double complexDistance(void) const =0
void maxAMSLAltitudeChanged(void)
virtual double maxAMSLAltitude(void) const =0
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
static const QString name
static constexpr const char * jsonComplexItemTypeValue
void rawValueChanged(const QVariant &value)
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(QGCMAVLink::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
virtual bool sendHomePositionToVehicle() const
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
static constexpr const char * jsonComplexItemTypeValue
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
static const QString name
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
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)
int lastSequenceNumber(void) const final
static MissionCommandTree * instance()
void minAMSLAltitudeChanged(double minAMSLAltitude)
void isROIActiveChanged(void)
void resumeMission(int resumeIndex)
double progressPct(void) const
bool showPlanFromManagerVehicle(void) final
void visualItemsChanged(void)
SendToVehiclePreCheckState sendToVehiclePreCheck(void)
void currentPlanViewVIIndexChanged(void)
bool dirty(void) const final
VisualMissionItem * insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem=false)
void isInsertTakeoffValidChanged(void)
void batteriesRequiredChanged(int batteriesRequired)
void isInsertLandValidChanged(void)
bool loadTextFile(QFile &file, QString &errorString)
void multipleLandPatternsAllowedChanged(void)
bool multipleLandPatternsAllowed(void) const
VisualMissionItem * insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
QGeoCoordinate takeoffCoordinate()
QmlObjectListModel *visualItems READ visualItems NOTIFY visualItemsChanged(QmlObjectTreeModel *visualItemsTree READ visualItemsTree CONSTANT) 1(QPersistentModelIndex planFileGroupIndex READ planFileGroupIndex CONSTANT) 1(QPersistentModelIndex defaultsGroupIndex READ defaultsGroupIndex CONSTANT) 1(QPersistentModelIndex missionGroupIndex READ missionGroupIndex CONSTANT) 1(QPersistentModelIndex fenceGroupIndex READ fenceGroupIndex CONSTANT) 1(QPersistentModelIndex rallyGroupIndex READ rallyGroupIndex CONSTANT) 1(QmlObjectListModel *simpleFlightPathSegments READ simpleFlightPathSegments CONSTANT) 1(QmlObjectListModel *directionArrows READ directionArrows CONSTANT) 1(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) 1(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) 1(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY previousCoordinateChanged) 1(FlightPathSegment *splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged) 1(double progressPct READ progressPct NOTIFY progressPctChanged) 1(int missionItemCount READ missionItemCount NOTIFY missionItemCountChanged) 1(int currentMissionIndex READ currentMissionIndex NOTIFY currentMissionIndexChanged) 1(int resumeMissionIndex READ resumeMissionIndex NOTIFY resumeMissionIndexChanged) 1(int currentPlanViewSeqNum READ currentPlanViewSeqNum NOTIFY currentPlanViewSeqNumChanged) 1(int currentPlanViewVIIndex READ currentPlanViewVIIndex NOTIFY currentPlanViewVIIndexChanged) 1(VisualMissionItem *currentPlanViewItem READ currentPlanViewItem NOTIFY currentPlanViewItemChanged) 1(TakeoffMissionItem *takeoffMissionItem READ takeoffMissionItem NOTIFY takeoffMissionItemChanged) 1(double missionTotalDistance READ missionTotalDistance NOTIFY missionTotalDistanceChanged) 1(double missionPlannedDistance READ missionPlannedDistance NOTIFY missionPlannedDistanceChanged) 1(double missionTime READ missionTime NOTIFY missionTimeChanged) 1(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged) 1(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged) 1(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged) 1(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged) 1(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged) 1(int batteryChangePoint READ batteryChangePoint NOTIFY batteryChangePointChanged) 1(int batteriesRequired READ batteriesRequired NOTIFY batteriesRequiredChanged) 1(QGCGeoBoundingCube *travelBoundingCube READ travelBoundingCube NOTIFY missionBoundingCubeChanged) 1(QString surveyComplexItemName READ surveyComplexItemName CONSTANT) 1(QString corridorScanComplexItemName READ corridorScanComplexItemName CONSTANT) 1(QString structureScanComplexItemName READ structureScanComplexItemName CONSTANT) 1(bool onlyInsertTakeoffValid MEMBER _onlyInsertTakeoffValid NOTIFY onlyInsertTakeoffValidChanged) 1(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY isInsertTakeoffValidChanged) 1(bool isInsertLandValid MEMBER _isInsertLandValid NOTIFY isInsertLandValidChanged) 1(bool hasLandItem MEMBER _hasLandItem NOTIFY hasLandItemChanged) 1(bool multipleLandPatternsAllowed READ multipleLandPatternsAllowed NOTIFY multipleLandPatternsAllowedChanged) 1(bool isROIActive MEMBER _isROIActive NOTIFY isROIActiveChanged) 1(bool isROIBeginCurrentItem MEMBER _isROIBeginCurrentItem NOTIFY isROIBeginCurrentItemChanged) 1(bool flyThroughCommandsAllowed MEMBER _flyThroughCommandsAllowed NOTIFY flyThroughCommandsAllowedChanged) 1(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged) 1(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged) 1(QGroundControlQmlGlobal in visualItemIndexForObject)(QObject *object) const
< Used by Plan view only for interactive editing
VisualMissionItem * insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void offsetMission(double eastMeters, double northMeters, double upMeters=0.0, bool offsetTakeoffItems=false, bool offsetLandingItems=false)
void setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
void maxAMSLAltitudeChanged(double maxAMSLAltitude)
void removeAllFromVehicle(void) final
void recalcTerrainProfile(void)
void missionPlannedDistanceChanged(double missionPlannedDistance)
void missionTotalDistanceChanged(double missionTotalDistance)
void hasLandItemChanged(void)
void _recalcFlightPathSegmentsSignal(void)
void complexMissionItemNamesChanged(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 onlyInsertTakeoffValidChanged(void)
void splitSegmentChanged(void)
void repositionMission(const QGeoCoordinate &newHome, bool repositionTakeoffItems=true, bool repositionLandingItems=true)
void resumeMissionReady(void)
SendToVehiclePreCheckState
@ SendToVehiclePreCheckStateFirwmareVehicleMismatch
@ SendToVehiclePreCheckStateNoActiveVehicle
@ SendToVehiclePreCheckStateOk
@ SendToVehiclePreCheckStateActiveMission
void batteryChangePointChanged(int batteryChangePoint)
void globalAltitudeModeChanged(void)
void rotateMission(double degreesCW, bool rotateTakeoffItems=false, bool rotateLandingItems=false)
void currentPlanViewSeqNumChanged(void)
void addMissionToKML(KMLPlanDomDocument &planKML)
void _recalcMissionFlightStatusSignal(void)
void flyThroughCommandsAllowedChanged(void)
void missionHoverDistanceChanged(double missionHoverDistance)
bool syncInProgress(void) const final
void sendToVehicle(void) final
void resumeMissionIndexChanged(void)
void currentMissionIndexChanged(int currentMissionIndex)
QGroundControlQmlGlobal::AltMode globalAltitudeMode(void)
VisualMissionItem * insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
QString surveyComplexItemName(void) const
void newItemsFromVehicle(void)
void save(QJsonObject &json) final
VisualMissionItem * insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void missionHoverTimeChanged(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
QGeoCoordinate plannedHomePosition(void) const
QString corridorScanComplexItemName(void) const
QString structureScanComplexItemName(void) const
bool containsItems(void) const final
void progressPctChanged(double progressPct)
void isROIBeginCurrentItemChanged(void)
void missionCruiseTimeChanged(void)
QStringList complexMissionItemNames(void) const
QGroundControlQmlGlobal::AltMode globalAltitudeModeDefault(void)
int readyForSaveState(void) const
void currentPlanViewItemChanged(void)
void previousCoordinateChanged(void)
void removeAll(void) final
Removes all from controller only.
void setGlobalAltitudeMode(QGroundControlQmlGlobal::AltMode altMode)
void missionBoundingCubeChanged(void)
void missionTimeChanged(void)
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 missionCruiseDistanceChanged(double missionCruiseDistance)
void resumeMissionUploadFail(void)
void loadFromVehicle(void) final
VisualMissionItem * insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem=false)
int resumeMissionIndex(void) const
void missionItemCountChanged(int missionItemCount)
VisualMissionItem * insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectListModel * visualItems(void)
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.
void setInitialHomePositionFromUser(const QGeoCoordinate &coordinate)
bool scanForMissionSettings(QmlObjectListModel *visualItems, int scanIndex)
Scans the loaded items for settings items.
QGeoCoordinate coordinate(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
void setInitialHomePosition(const QGeoCoordinate &coordinate)
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)
int count READ count NOTIFY countChanged(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) bool dirty() const
void syncInProgressChanged(bool syncInProgress)
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)
Fact *allowMultipleLandingPatterns READ allowMultipleLandingPatterns CONSTANT Fact * allowMultipleLandingPatterns()
Fact *showGimbalOnlyWhenSet READ showGimbalOnlyWhenSet CONSTANT Fact * showGimbalOnlyWhenSet()
Fact *takeoffItemNotRequired READ takeoffItemNotRequired CONSTANT Fact * takeoffItemNotRequired()
static VehicleClass_t vehicleClass(MAV_TYPE mavType)
static constexpr const VehicleClass_t VehicleClassFixedWing
static constexpr const VehicleClass_t VehicleClassMultiRotor
static MAV_TYPE vehicleClassToMavType(VehicleClass_t vehicleClass)
static FirmwareClass_t firmwareClass(MAV_AUTOPILOT autopilot)
static constexpr const VehicleClass_t VehicleClassGeneric
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
void setDirty(bool dirty) override final
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.
QObject * removeItem(const QModelIndex &index)
QObject * removeAt(const QModelIndex &parentIndex, int row)
QModelIndex index(int row, int column, const QModelIndex &parent=QModelIndex()) const override
QModelIndex insertItem(int row, QObject *object, const QModelIndex &parentIndex=QModelIndex())
Inserts object at row under parentIndex. Returns the new item's index.
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.
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
QGroundControlQmlGlobal::AltMode altitudeMode(void) const
QGeoCoordinate entryCoordinate(void) const final
bool scanForSections(QmlObjectListModel *visualItems, int scanIndex, PlanMasterController *masterController)
double specifiedVehicleYaw(void) override
int lastSequenceNumber(void) const final
MAV_CMD mavCommand(void) const
bool specifiesAltitude(void) const
QGeoCoordinate coordinate(void) const final
void setAltitudeMode(QGroundControlQmlGlobal::AltMode altitudeMode)
virtual bool load(QTextStream &loadStream)
void setCoordinate(const QGeoCoordinate &coordinate) override
void setCommand(int command)
MissionItem & missionItem(void)
int lastSequenceNumber(void) const final
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
static const QString name
static constexpr const char * jsonComplexItemTypeValue
static constexpr const char * jsonComplexItemTypeValue
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
static const QString name
static bool isTakeoffCommand(MAV_CMD command)
bool load(QTextStream &loadStream) final
int lastSequenceNumber(void) const final
int sequenceNumber(void) const final
static const QString name
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
static constexpr const char * jsonComplexItemTypeValue
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
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 setDistanceFromStart(double distanceFromStart)
void setHasCurrentChildItem(bool hasCurrentChildItem)
void specifiedVehicleYawChanged(void)
virtual void setCoordinate(const QGeoCoordinate &coordinate)=0
virtual int sequenceNumber(void) const =0
void setTerrainCollision(bool terrainCollision)
virtual void applyNewAltitude(double newAltitude)=0
Adjust the altitude of the item if appropriate to the new altitude.
void setAltDifference(double altDifference)
void setMissionVehicleYaw(double vehicleYaw)
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)
virtual double amslExitAlt(void) const =0
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)
virtual double specifiedGimbalPitch(void)=0
void specifiedFlightSpeedChanged(void)
void clearSimpleFlighPathSegment(void)
void currentVTOLModeChanged(void)
Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
void setDistance(double distance)
virtual void setSequenceNumber(int sequenceNumber)=0
virtual double specifiedGimbalYaw(void)=0
virtual double specifiedFlightSpeed(void)=0
virtual double amslEntryAlt(void) const =0
void setAltPercent(double altPercent)
virtual ReadyForSaveState readyForSaveState(void) const
void specifiedGimbalYawChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
void setTerrainPercent(double terrainPercent)
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus)
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 double additionalTimeDelay(void) const =0
virtual bool specifiesCoordinate(void) const =0
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void setAzimuth(double azimuth)
void additionalTimeDelayChanged(void)
virtual void save(QJsonArray &missionItems)=0
virtual QGeoCoordinate exitCoordinate(void) const =0
VisualMissionItem * parentItem(void)
virtual QGeoCoordinate entryCoordinate(void) const =0
double terrainAltitude(void) const
virtual double editableAlt(void) const =0
bool validateExternalQGCJsonFile(const QJsonObject &jsonObject, const QString &expectedFileType, int minSupportedVersion, int maxSupportedVersion, int &version, QString &errorString)
returned error string if validation fails
constexpr const char * jsonVersionKey
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
void saveGeoCoordinate(const QGeoCoordinate &coordinate, bool writeAltitude, QJsonValue &jsonValue, bool geoJsonFormat=false)
bool loadGeoCoordinate(const QJsonValue &jsonValue, bool altitudeRequired, QGeoCoordinate &coordinate, QString &errorString, bool geoJsonFormat=false)
if true, use [lon, lat], [lat, lon] otherwise
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
double hoverAmpsTotal
Total hover amps used.
double gimbalPitch
NaN signals pitch was never changed.
QGCMAVLink::VehicleClass_t vtolMode
Either VehicleClassFixedWing, VehicleClassMultiRotor, VehicleClassGeneric (mode unknown)
int mAhBattery
0 for not available
int batteryChangePoint
-1 for not supported, 0 for not needed
double cruiseAmps
Amp consumption during cruise.
double ampMinutesAvailable
Amp minutes available from single battery.
double cruiseAmpsTotal
Total cruise amps used.
double gimbalYaw
NaN signals yaw was never changed.
double maxTelemetryDistance
double hoverAmps
Amp consumption during hover.
int batteriesRequired
-1 for not supported