QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LandingComplexItem.cc
Go to the documentation of this file.
2#include "AppMessages.h"
3#include "QGCApplication.h"
4#include "GeoJsonHelper.h"
5#include "JsonParsing.h"
6#include "MissionController.h"
9#include "SimpleMissionItem.h"
11#include "TakeoffMissionItem.h"
12#include "MissionItem.h"
13#include "Fact.h"
14#include "CameraSection.h"
15#include "Vehicle.h"
16#include "QGCLoggingCategory.h"
17
18QGC_LOGGING_CATEGORY(LandingComplexItemLog, "Plan.LandingComplexItem")
19
21 : ComplexMissionItem (masterController, flyView)
22{
23 _isIncomplete = false;
24
25 // The following is used to compress multiple recalc calls in a row to into a single call.
27 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&LandingComplexItem::_updateFlightPathSegmentsSignal));
28}
29
31{
33 // ArduPilot does not support camera commands
36 }
37
40
41 connect(loiterRadius(), &Fact::valueChanged, this, &LandingComplexItem::_recalcFromRadiusChange);
42 connect(loiterClockwise(), &Fact::rawValueChanged, this, &LandingComplexItem::_recalcFromRadiusChange);
43
44 connect(useLoiterToAlt(), &Fact::rawValueChanged, this, &LandingComplexItem::_recalcFromApproachModeChange);
45
48
49 // The main coordinate is aliased to the exit (landing point) because that's the core of this complex item and the master for all transformations
51
54
69
70 connect(stopTakingPhotos(), &Fact::valueChanged, this, &LandingComplexItem::_signalLastSequenceNumberChanged);
71 connect(stopTakingVideo(), &Fact::valueChanged, this, &LandingComplexItem::_signalLastSequenceNumberChanged);
72
79
82
86
94
96
97 connect(finalApproachAltitude(), &Fact::valueChanged, this, &LandingComplexItem::_updateFinalApproachCoodinateAltitudeFromFact);
98 connect(landingAltitude(), &Fact::valueChanged, this, &LandingComplexItem::_updateLandingCoodinateAltitudeFromFact);
99}
100
102{
104 if (takeoffMissionItem && takeoffMissionItem->specifiesCoordinate()) {
105 qreal heading = takeoffMissionItem->launchCoordinate().azimuthTo(takeoffMissionItem->coordinate());
106 landingHeading()->setRawValue(heading);
107 }
108}
109
111{
113}
114
115void LandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
116{
119 if (_landingCoordSet) {
121 } else {
124 _ignoreRecalcSignals = false;
125 _landingCoordSet = true;
127 emit landingCoordSetChanged(true);
128 }
129 }
130}
131
139
140QPointF LandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
141{
142 QPointF rotated;
143 double radians = (M_PI / 180.0) * angle;
144
145 rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
146 rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());
147
148 return rotated;
149}
150
152{
153 // Fixed:
154 // land
155 // heading
156 // distance
157 // radius
158 // Adjusted:
159 // final approach
160 // slope start
161
163 // These are our known values
164 double distance = landingDistance()->rawValue().toDouble();
165 double heading = landingHeading()->rawValue().toDouble();
166
167 // Heading is from slope start to land, hence +180
168 _slopeStartCoordinate = _landingCoordinate.atDistanceAndAzimuth(distance, heading + 180);
169
170 if (useLoiterToAlt()->rawValue().toBool()) {
171 double radius = loiterRadius()->rawValue().toDouble();
172
173 // Loiter coord is 90 degrees counter clockwise from tangent coord
174 _finalApproachCoordinate = _slopeStartCoordinate.atDistanceAndAzimuth(radius, heading - 180 + (_loiterClockwise()->rawValue().toBool() ? -90 : 90));
175 } else {
177 }
178
179 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
180
185 _ignoreRecalcSignals = false;
186 }
187}
188
189void LandingComplexItem::_recalcFromRadiusChange(void)
190{
191 // Fixed:
192 // land
193 // slope start
194 // distance
195 // radius
196 // heading
197 // Adjusted:
198 // loiter
199
201 // These are our known values
202 double radius = loiterRadius()->rawValue().toDouble();
203 double distance = landingDistance()->rawValue().toDouble();
204 double heading = landingHeading()->rawValue().toDouble();
205
206 double landToLoiterDistance = _landingCoordinate.distanceTo(_finalApproachCoordinate);
207 if (landToLoiterDistance < radius) {
208 // Degnenerate case: Move tangent to loiter point
210
211 double slopeStartHeading = _landingCoordinate.azimuthTo(_slopeStartCoordinate);
212
214 landingHeading()->setRawValue(slopeStartHeading);
216 _ignoreRecalcSignals = false;
217 } else {
218 double loiterDistance = qSqrt(qPow(radius, 2) + qPow(distance, 2));
219 double angleLoiterToTangent = qRadiansToDegrees(qAsin(radius/loiterDistance)) * (_loiterClockwise()->rawValue().toBool() ? -1 : 1);
220
221 _finalApproachCoordinate = _landingCoordinate.atDistanceAndAzimuth(loiterDistance, heading + 180 + angleLoiterToTangent);
222 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
223
226 _ignoreRecalcSignals = false;
227 }
228 }
229}
230
231void LandingComplexItem::_recalcFromApproachModeChange(void)
232{
233 // Fixed:
234 // land
235 // slope start
236 // heading
237 // distance
238 // Adjusted:
239 // final approach
240
242 if (useLoiterToAlt()->rawValue().toBool()) {
243 double radius = loiterRadius()->rawValue().toDouble();
244 double offsetAngle =
245 landingHeading()->rawValue().toDouble() - 180 +
246 (_loiterClockwise()->rawValue().toBool() ? -90 : 90);
247
249 _slopeStartCoordinate.atDistanceAndAzimuth(radius, offsetAngle);
250 } else {
252 }
253
254 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
255
259 _ignoreRecalcSignals = false;
260 }
261}
262
264{
265 // Fixed:
266 // land
267 // final approach
268 // radius
269 // Adjusted:
270 // heading
271 // distance
272 // slope start
273
275 double distance;
276
277 if (useLoiterToAlt()->rawValue().toBool()) {
278 // These are our known values
279 double radius = loiterRadius()->rawValue().toDouble();
280 double landToLoiterDistance = _landingCoordinate.distanceTo(_finalApproachCoordinate);
281 double landToLoiterHeading = _landingCoordinate.azimuthTo(_finalApproachCoordinate);
282
283 if (landToLoiterDistance < radius) {
284 // Degenerate case: tangent at loiter coordinate
287 } else {
288 // Calculate tangent point using circle geometry
289 double loiterToTangentAngle = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (_loiterClockwise()->rawValue().toBool() ? 1 : -1);
290 distance = qSqrt(qPow(landToLoiterDistance, 2) - qPow(radius, 2));
291 _slopeStartCoordinate = _landingCoordinate.atDistanceAndAzimuth(distance, landToLoiterHeading + loiterToTangentAngle);
292 }
293 } else {
296 }
297
298 double heading = _slopeStartCoordinate.azimuthTo(_landingCoordinate);
299
301 landingHeading()->setRawValue(heading);
305 _ignoreRecalcSignals = false;
306 }
307}
308
310{
311 // Fixed items are:
312 // land start, loiter, land
313 // Optional items are:
314 // stop photos/video
315 return _sequenceNumber + 2 + (stopTakingPhotos()->rawValue().toBool() ? 2 : 0) + (stopTakingVideo()->rawValue().toBool() ? 1 : 0);
316}
317
318void LandingComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
319{
320 int seqNum = _sequenceNumber;
321
322 // IMPORTANT NOTE: Any changes here must also be taken into account in scanForItem
323
324 MissionItem* item = _createDoLandStartItem(seqNum++, missionItemParent);
325 items.append(item);
326
327 if (useDoChangeSpeed()->rawValue().toBool()) {
328 item = _createDoChangeSpeedItem(SPEED_TYPE_AIRSPEED, finalApproachSpeed()->rawValue().toDouble(), -1, seqNum++, missionItemParent);
329 items.append(item);
330 }
331
332 if (stopTakingPhotos()->rawValue().toBool()) {
333 CameraSection::appendStopTakingPhotos(items, seqNum, missionItemParent);
334 }
335
336 if (stopTakingVideo()->rawValue().toBool()) {
337 CameraSection::appendStopTakingVideo(items, seqNum, missionItemParent);
338 }
339
340 item = _createFinalApproachItem(seqNum++, missionItemParent);
341 items.append(item);
342
343 item = _createLandItem(seqNum++,
345 _landingCoordinate.latitude(), _landingCoordinate.longitude(), landingAltitude()->rawValue().toDouble(),
346 missionItemParent);
347 items.append(item);
348}
349
351{
352 auto doLandStartItem =
353 new MissionItem(seqNum, // sequence number
354 MAV_CMD_DO_LAND_START, // MAV_CMD
355 MAV_FRAME_MISSION, // MAV_FRAME
356 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 1-7
357 true, // autoContinue
358 false, // isCurrentItem
359 parent);
360
361 bool firmwareAllowsDoLandStartCoords =
364 MAV_CMD_DO_LAND_START)
366
367 // This allows skipping the coordinates for firmware that doesn't require
368 // them, keeping the flight plan simpler. The expression can be expanded to
369 // include any additional firmware versions where this is the case.
370 bool firmwareRequiresDoLandStartCoords =
373
374 if (firmwareAllowsDoLandStartCoords && firmwareRequiresDoLandStartCoords) {
375 doLandStartItem->setFrame(_altitudesAreRelative
376 ? MAV_FRAME_GLOBAL_RELATIVE_ALT
377 : MAV_FRAME_GLOBAL);
378
379 doLandStartItem->setParam5(_finalApproachCoordinate.latitude());
380 doLandStartItem->setParam6(_finalApproachCoordinate.longitude());
381 doLandStartItem->setParam7(
382 _finalApproachAltitude()->rawValue().toFloat());
383 }
384
385 return doLandStartItem;
386}
387
388MissionItem* LandingComplexItem::_createDoChangeSpeedItem(int speedType, int speedValue, int throttlePercentage, int seqNum, QObject* parent)
389{
390 return new MissionItem(seqNum++, // sequence number
391 MAV_CMD_DO_CHANGE_SPEED, // MAV_CMD
392 MAV_FRAME_MISSION, // MAV_FRAME
393 speedType, speedValue, throttlePercentage, // param 1-3
394 0.0, 0.0, 0.0, 0.0, // param 4-7
395 true, // autoContinue
396 false, // isCurrentItem
397 parent);
398}
399
401{
402 if (useLoiterToAlt()->rawValue().toBool()) {
403 return new MissionItem(seqNum,
404 MAV_CMD_NAV_LOITER_TO_ALT,
405 _altitudesAreRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
406 1.0, // Heading required = true
407 loiterRadius()->rawValue().toDouble() * (_loiterClockwise()->rawValue().toBool() ? 1.0 : -1.0),
408 0.0, // param 3 - unused
409 1.0, // Exit crosstrack - tangent of loiter to land point
410 _finalApproachCoordinate.latitude(),
411 _finalApproachCoordinate.longitude(),
412 _finalApproachAltitude()->rawValue().toFloat(),
413 true, // autoContinue
414 false, // isCurrentItem
415 parent);
416 } else {
417 return new MissionItem(seqNum,
418 MAV_CMD_NAV_WAYPOINT,
419 _altitudesAreRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
420 0, // No hold time
421 0, // Use default acceptance radius
422 0, // Pass through waypoint
423 qQNaN(), // Yaw not specified
424 _finalApproachCoordinate.latitude(),
425 _finalApproachCoordinate.longitude(),
426 _finalApproachAltitude()->rawValue().toFloat(),
427 true, // autoContinue
428 false, // isCurrentItem
429 parent);
430 }
431}
432
433bool LandingComplexItem::_scanForItems(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
434{
435 qCDebug(LandingComplexItemLog) << "VTOLLandingComplexItem::scanForItem count" << visualItems->count();
436
437 if (visualItems->count() < 3) {
438 return false;
439 }
440
441 // Start looking for the commands in reverse order from the end of the list
442 int startIndex = visualItems->count();
443 bool foundAny = false;
444
445 while (startIndex >= 0) {
446 if (_scanForItem(visualItems, startIndex, flyView, masterController, isLandItemFunc, createItemFunc)) {
447 foundAny = true;
448 } else {
449 startIndex--;
450 }
451 }
452
453 return foundAny;
454}
455
456bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, int& startIndex, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
457{
458 // A valid landing pattern is comprised of the follow commands in this order at the end of the item list:
459 // MAV_CMD_DO_LAND_START - required
460 // MAV_CMD_DO_CHANGE_SPEED - optional
461 // Stop taking photos sequence - optional
462 // Stop taking video sequence - optional
463 // MAV_CMD_NAV_LOITER_TO_ALT or MAV_CMD_NAV_WAYPOINT
464 // MAV_CMD_NAV_LAND or MAV_CMD_NAV_VTOL_LAND
465
466 int scanIndex = startIndex - 1;
467
468 if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
469 return false;
470 }
471 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex--);
472 if (!item) {
473 return false;
474 }
475 MissionItem& missionItemLand = item->missionItem();
476 if (!isLandItemFunc(missionItemLand)) {
477 return false;
478 }
479 MAV_FRAME landPointFrame = missionItemLand.frame();
480
481 if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
482 return false;
483 }
484 item = visualItems->value<SimpleMissionItem*>(scanIndex);
485 if (!item) {
486 return false;
487 }
488 bool useLoiterToAlt = true;
489 MissionItem& missionItemFinalApproach = item->missionItem();
490 if (missionItemFinalApproach.command() == MAV_CMD_NAV_LOITER_TO_ALT) {
491 if (missionItemFinalApproach.frame() != landPointFrame ||
493 // APM automatically changes the value of param1 to 1, so when sending a plan it will
494 // be 0, and when downloading it, the value will be 1
495 ? missionItemFinalApproach.param1() != 0.0 && missionItemFinalApproach.param1() != 1.0
496 : missionItemFinalApproach.param1() != 1.0) ||
497 missionItemFinalApproach.param3() != 0 || missionItemFinalApproach.param4() != 1.0) {
498 return false;
499 }
500 } else if (missionItemFinalApproach.command() == MAV_CMD_NAV_WAYPOINT) {
501 if (missionItemFinalApproach.frame() != landPointFrame ||
502 missionItemFinalApproach.param1() != 0 || missionItemFinalApproach.param2() != 0 || missionItemFinalApproach.param3() != 0 ||
503 (!masterController->managerVehicle()->apmFirmware() && !qIsNaN(missionItemFinalApproach.param4())) ||
504 qIsNaN(missionItemFinalApproach.param5()) || qIsNaN(missionItemFinalApproach.param6()) || qIsNaN(missionItemFinalApproach.param6())) {
505 return false;
506 }
507 useLoiterToAlt = false;
508 } else {
509 return false;
510 }
511
513 bool stopTakingVideo = CameraSection::scanStopTakingVideo(visualItems, scanIndex, false /* removeScannedItems */);
514 if (!stopTakingVideo) {
516 }
517
519 bool stopTakingPhotos = CameraSection::scanStopTakingPhotos(visualItems, scanIndex, false /* removeScannedItems */);
520 if (!stopTakingPhotos) {
522 }
523
524 scanIndex--;
525 bool useDoChangeSpeed = false;
526 double finalApproachSpeed = 0;
527 if (scanIndex >= 0 && scanIndex < visualItems->count()) {
528 item = visualItems->value<SimpleMissionItem*>(scanIndex);
529 if (item) {
530 MissionItem& missionItemChangeSpeed = item->missionItem();
531 if (missionItemChangeSpeed.command() == MAV_CMD_DO_CHANGE_SPEED &&
532 missionItemChangeSpeed.param1() == static_cast<double>(SPEED_TYPE_AIRSPEED) &&
533 missionItemChangeSpeed.param2() >= -2 &&
534 missionItemChangeSpeed.param3() == -1 &&
535 missionItemChangeSpeed.param4() == 0) {
536 useDoChangeSpeed = true;
537 finalApproachSpeed = missionItemChangeSpeed.param2();
538 }
539 }
540 }
541 if (!useDoChangeSpeed) {
542 scanIndex++;
543 }
544
545 scanIndex--;
546 if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
547 return false;
548 }
549 item = visualItems->value<SimpleMissionItem*>(scanIndex);
550 if (!item) {
551 return false;
552 }
553 MissionItem& missionItemDoLandStart = item->missionItem();
554 if (missionItemDoLandStart.command() != MAV_CMD_DO_LAND_START ||
555 missionItemDoLandStart.param1() != 0 || missionItemDoLandStart.param2() != 0 || missionItemDoLandStart.param3() != 0 || missionItemDoLandStart.param4() != 0 ||
556 missionItemDoLandStart.param5() != 0 || missionItemDoLandStart.param6() != 0 || missionItemDoLandStart.param7() != 0) {
557 return false;
558 }
559
560 // We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission.
561 int deleteCount = 3;
562 if (stopTakingPhotos) {
564 }
565 if (stopTakingVideo) {
567 }
568 if (useDoChangeSpeed) {
569 deleteCount++;
570 }
571 int firstItem = startIndex - deleteCount;
572 while (deleteCount--) {
573 visualItems->removeAt(firstItem)->deleteLater();
574 }
575
576 // Now stuff all the scanned information into the item
577
578 LandingComplexItem* complexItem = createItemFunc(masterController, flyView);
579
580 complexItem->_ignoreRecalcSignals = true;
581
582 complexItem->_altitudesAreRelative = landPointFrame == MAV_FRAME_GLOBAL_RELATIVE_ALT;
583 complexItem->setFinalApproachCoordinate(QGeoCoordinate(missionItemFinalApproach.param5(), missionItemFinalApproach.param6()));
584 complexItem->finalApproachAltitude()->setRawValue(missionItemFinalApproach.param7());
587
588 if (useDoChangeSpeed) {
590 }
591 if (useLoiterToAlt) {
592 complexItem->loiterRadius()->setRawValue(qAbs(missionItemFinalApproach.param2()));
593 complexItem->loiterClockwise()->setRawValue(missionItemFinalApproach.param2() > 0);
594 }
595
596 complexItem->_landingCoordinate.setLatitude(missionItemLand.param5());
597 complexItem->_landingCoordinate.setLongitude(missionItemLand.param6());
598 complexItem->landingAltitude()->setRawValue(missionItemLand.param7());
599
602
603 complexItem->_landingCoordSet = true;
604
605 complexItem->_ignoreRecalcSignals = false;
606
607 complexItem->_recalcFromCoordinateChange();
608 complexItem->setDirty(false);
609
610 visualItems->insert(firstItem, complexItem);
611 startIndex = firstItem;
612
613 return true;
614}
615
617{
618 finalApproachAltitude()->setRawValue(newAltitude);
619}
620
625
627{
628 if (_dirty != dirty) {
629 _dirty = dirty;
630 emit dirtyChanged(_dirty);
631 }
632}
633
635{
636 setDirty(true);
637}
638
639void LandingComplexItem::setCoordinate(const QGeoCoordinate& coordinate) {
640 if (!_landingCoordSet) {
642 return;
643 }
644
645 // Move entire complex item, preserving heading and distance
648 _ignoreRecalcSignals = false;
650}
651
660
662{
663 return finalApproachAltitude()->rawValue().toDouble();
664}
665
667{
669}
670
672{
673 return landingAltitude()->rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);
674
675}
676
677void LandingComplexItem::_signalLastSequenceNumberChanged(void)
678{
680}
681
682void LandingComplexItem::_updateFinalApproachCoodinateAltitudeFromFact(void)
683{
684 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
686}
687
688void LandingComplexItem::_updateLandingCoodinateAltitudeFromFact(void)
689{
690 _landingCoordinate.setAltitude(landingAltitude()->rawValue().toDouble());
692}
693
694double LandingComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
695{
696 return qMax(_finalApproachCoordinate.distanceTo(other),_landingCoordinate.distanceTo(other));
697}
698
700{
701 QJsonObject saveObject;
702
703 QGeoCoordinate coordinate;
704 QJsonValue jsonCoordinate;
705
707 coordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
708 GeoJsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
709 saveObject[_jsonFinalApproachCoordinateKey] = jsonCoordinate;
710
711 saveObject[_jsonUseDoChangeSpeedKey] = useDoChangeSpeed()->rawValue().toBool();
712 saveObject[_jsonFinalApproachSpeedKey] = finalApproachSpeed()->rawValue().toDouble();
713
715 coordinate.setAltitude(landingAltitude()->rawValue().toDouble());
716 GeoJsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
717 saveObject[_jsonLandingCoordinateKey] = jsonCoordinate;
718
719 saveObject[_jsonLoiterRadiusKey] = loiterRadius()->rawValue().toDouble();
720 saveObject[_jsonStopTakingPhotosKey] = stopTakingPhotos()->rawValue().toBool();
721 saveObject[_jsonStopTakingVideoKey] = stopTakingVideo()->rawValue().toBool();
722 saveObject[_jsonLoiterClockwiseKey] = loiterClockwise()->rawValue().toBool();
723 saveObject[_jsonUseLoiterToAltKey] = useLoiterToAlt()->rawValue().toBool();
725
726 return saveObject;
727}
728
729bool LandingComplexItem::_load(const QJsonObject& complexObject, int sequenceNumber, const QString& jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString& errorString)
730{
731 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
732 { JsonParsing::jsonVersionKey, QJsonValue::Double, true },
733 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
734 { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
735 { _jsonDeprecatedLoiterCoordinateKey, QJsonValue::Array, false }, // Loiter changed to Final Approach
736 { _jsonFinalApproachCoordinateKey, QJsonValue::Array, false },
737 { _jsonUseDoChangeSpeedKey, QJsonValue::Bool, false },
738 { _jsonFinalApproachSpeedKey, QJsonValue::Double, false },
739 { _jsonLoiterRadiusKey, QJsonValue::Double, true },
740 { _jsonLoiterClockwiseKey, QJsonValue::Bool, true },
741 { _jsonLandingCoordinateKey, QJsonValue::Array, true },
742 { _jsonStopTakingPhotosKey, QJsonValue::Bool, false },
743 { _jsonStopTakingVideoKey, QJsonValue::Bool, false },
744 { _jsonUseLoiterToAltKey, QJsonValue::Bool, false },
745 };
746 if (!JsonParsing::validateKeys(complexObject, keyInfoList, errorString)) {
747 return false;
748 }
749
750 if (!complexObject.contains(_jsonDeprecatedLoiterCoordinateKey) && !complexObject.contains(_jsonFinalApproachCoordinateKey)) {
751 QList<JsonParsing::KeyValidateInfo> finalApproachKeyInfoList = {
752 { _jsonFinalApproachCoordinateKey, QJsonValue::Array, true },
753 };
754 if (!JsonParsing::validateKeys(complexObject, finalApproachKeyInfoList, errorString)) {
755 return false;
756 }
757 }
758
759 QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
760 QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
761 if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
762 errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(QCoreApplication::applicationName()).arg(itemType).arg(complexType);
763 return false;
764 }
765
767
769
770 if (useDeprecatedRelAltKeys) {
771 QList<JsonParsing::KeyValidateInfo> v1KeyInfoList = {
772 { _jsonDeprecatedLoiterAltitudeRelativeKey, QJsonValue::Bool, true },
773 { _jsonDeprecatedLandingAltitudeRelativeKey, QJsonValue::Bool, true },
774 };
775 if (!JsonParsing::validateKeys(complexObject, v1KeyInfoList, errorString)) {
776 return false;
777 }
778
779 bool loiterAltitudeRelative = complexObject[_jsonDeprecatedLoiterAltitudeRelativeKey].toBool();
780 bool landingAltitudeRelative = complexObject[_jsonDeprecatedLandingAltitudeRelativeKey].toBool();
781 if (loiterAltitudeRelative != landingAltitudeRelative) {
782 QGC::showAppMessage(tr("Fixed Wing Landing Pattern: "
783 "Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
784 "Both have been set to relative altitude. Be sure to adjust/check your plan prior to flight."));
786 } else {
787 _altitudesAreRelative = loiterAltitudeRelative;
788 }
789 } else {
790 QList<JsonParsing::KeyValidateInfo> v2KeyInfoList = {
791 { _jsonAltitudesAreRelativeKey, QJsonValue::Bool, true },
792 };
793 if (!JsonParsing::validateKeys(complexObject, v2KeyInfoList, errorString)) {
794 _ignoreRecalcSignals = false;
795 return false;
796 }
797 _altitudesAreRelative = complexObject[_jsonAltitudesAreRelativeKey].toBool();
798 }
799
800 QGeoCoordinate coordinate;
802 if (!GeoJsonHelper::loadGeoCoordinate(complexObject[finalApproachKey], true /* altitudeRequired */, coordinate, errorString)) {
803 return false;
804 }
807
808 useDoChangeSpeed()->setRawValue(complexObject[_jsonUseDoChangeSpeedKey].toBool(false));
810 ? complexObject[_jsonFinalApproachSpeedKey].toDouble()
812
813 if (!GeoJsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
814 return false;
815 }
818
819 loiterRadius()->setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble());
820 loiterClockwise()->setRawValue(complexObject[_jsonLoiterClockwiseKey].toBool());
821 useLoiterToAlt()->setRawValue(complexObject[_jsonUseLoiterToAltKey].toBool(true));
822 stopTakingPhotos()->setRawValue(complexObject[_jsonStopTakingPhotosKey].toBool(false));
823 stopTakingVideo()->setRawValue(complexObject[_jsonStopTakingVideoKey].toBool(false));
824
826
827 _landingCoordSet = true;
828 _ignoreRecalcSignals = false;
829
831 // These will kick off terrain query
834
835 return true;
836}
837
#define qgcApp()
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static int stopTakingPhotosCommandCount(void)
static void appendStopTakingVideo(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
static void appendStopTakingPhotos(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
static bool scanStopTakingVideo(QmlObjectListModel *visualItems, int scanIndex, bool removeScannedItems)
static int stopTakingVideoCommandCount(void)
static bool scanStopTakingPhotos(QmlObjectListModel *visualItems, int scanIndex, bool removeScannedItems)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
void maxAMSLAltitudeChanged(void)
void patternNameChanged(void)
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
QVariant rawDefaultValue() const
Definition Fact.cc:443
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
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 ...
Q_INVOKABLE void setLandingHeadingToTakeoffHeading()
const Fact * landingAltitude(void) const
virtual void _updateFlightPathSegmentsDontCallDirectly(void)=0
QJsonObject _save(void)
void landingCoordSetChanged(bool landingCoordSet)
virtual const Fact * _loiterClockwise(void) const =0
static constexpr const char * _jsonAltitudesAreRelativeKey
const Fact * finalApproachSpeed(void) const
static bool _scanForItem(QmlObjectListModel *visualItems, int &startIndex, bool flyView, PlanMasterController *masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
static constexpr const char * _jsonStopTakingVideoKey
static constexpr const char * _jsonStopTakingPhotosKey
QGeoCoordinate _slopeStartCoordinate
void _recalcFromCoordinateChange(void)
static constexpr const char * _jsonDeprecatedLoiterAltitudeRelativeKey
double amslEntryAlt(void) const final
void setSequenceNumber(int sequenceNumber) final
bool _load(const QJsonObject &complexObject, int sequenceNumber, const QString &jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString &errorString)
const Fact * loiterClockwise(void) const
QGeoCoordinate _finalApproachCoordinate
void setLandingCoordinate(const QGeoCoordinate &coordinate)
static constexpr const char * _jsonFinalApproachSpeedKey
QGeoCoordinate slopeStartCoordinate(void) const
const Fact * landingDistance(void) const
void applyNewAltitude(double newAltitude) final
Adjust the altitude of the item if appropriate to the new altitude.
void finalApproachCoordinateChanged(QGeoCoordinate coordinate)
double greatestDistanceTo(const QGeoCoordinate &other) const final
void setDirty(bool dirty) final
void altitudesAreRelativeChanged(bool altitudesAreRelative)
static constexpr const char * _jsonFinalApproachCoordinateKey
static bool _scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
static constexpr const char * _jsonLoiterClockwiseKey
QGeoCoordinate coordinate(void) const final
MissionItem * _createDoLandStartItem(int seqNum, QObject *parent)
void _updateFlightPathSegmentsSignal(void)
static constexpr const char * _jsonUseDoChangeSpeedKey
bool altitudesAreRelative(void) const
void landingCoordinateChanged(QGeoCoordinate coordinate)
double complexDistance(void) const final
ReadyForSaveState readyForSaveState(void) const final
QGeoCoordinate finalApproachCoordinate(void) const
void slopeStartCoordinateChanged(QGeoCoordinate coordinate)
const Fact * stopTakingPhotos(void) const
const Fact * useDoChangeSpeed(void) const
static constexpr const char * _jsonLoiterRadiusKey
MissionItem * _createDoChangeSpeedItem(int speedType, int speedValue, int throttlePercentage, int seqNum, QObject *parent)
static constexpr const char * _jsonUseLoiterToAltKey
const Fact * landingHeading(void) const
int lastSequenceNumber(void) const final
QGeoCoordinate landingCoordinate(void) const
void setCoordinate(const QGeoCoordinate &coordinate) final
double amslExitAlt(void) const final
virtual void _calcGlideSlope(void)=0
const Fact * useLoiterToAlt(void) const
MissionItem * _createFinalApproachItem(int seqNum, QObject *parent)
QGeoCoordinate _landingCoordinate
static constexpr const char * _jsonLandingCoordinateKey
void _recalcFromHeadingAndDistanceChange(void)
const Fact * loiterRadius(void) const
static constexpr const char * _jsonDeprecatedLandingAltitudeRelativeKey
void setAltitudesAreRelative(bool altitudesAreRelative)
double editableAlt(void) const final
const Fact * stopTakingVideo(void) const
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
virtual const Fact * _finalApproachAltitude(void) const =0
QPointF _rotatePoint(const QPointF &point, const QPointF &origin, double angle)
int sequenceNumber(void) const final
void setFinalApproachCoordinate(const QGeoCoordinate &coordinate)
static constexpr const char * _jsonDeprecatedLoiterCoordinateKey
virtual MissionItem * _createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject *parent)=0
const Fact * finalApproachAltitude(void) const
bool dirty(void) const final
static MissionCommandTree * instance()
const MissionCommandUIInfo * getUIInfo(Vehicle *vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
bool specifiesCoordinate(void) const
void _recalcFlightPathSegmentsSignal(void)
TakeoffMissionItem * takeoffMissionItem(void) const
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
QGeoCoordinate plannedHomePosition(void) const
MAV_CMD command(void) const
Definition MissionItem.h:49
double param5(void) const
Definition MissionItem.h:58
double param7(void) const
Definition MissionItem.h:60
MAV_FRAME frame(void) const
Definition MissionItem.h:52
double param3(void) const
Definition MissionItem.h:56
double param6(void) const
Definition MissionItem.h:59
double param1(void) const
Definition MissionItem.h:54
double param4(void) const
Definition MissionItem.h:57
double param2(void) const
Definition MissionItem.h:55
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
T value(int index) const
QObject * removeAt(int index)
int count() const override final
void insert(int index, QObject *object)
A SimpleMissionItem is used to represent a single MissionItem to the ui.
bool specifiesCoordinate(void) const final
QGeoCoordinate coordinate(void) const final
MissionItem & missionItem(void)
Takeoff mission item is a special case of a SimpleMissionItem which supports Launch Location display/...
QGeoCoordinate launchCoordinate(void) const
bool apmFirmware() const
Definition Vehicle.h:495
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
Definition Vehicle.cc:2743
PlanMasterController * _masterController
bool flyView(void) const
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
void amslExitAltChanged(double alt)
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void coordinateChanged(const QGeoCoordinate &coordinate)
QGCMAVLinkTypes::VehicleClass_t _previousVTOLMode
Generic == unknown.
void readyForSaveStateChanged(void)
MissionController * _missionController
double distance(void) const
void amslEntryAltChanged(double alt)
bool _wizardMode
true: Item editor is showing wizard completion panel
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
void sequenceNumberChanged(int sequenceNumber)
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
PlanMasterController * masterController(void)
void wizardModeChanged(bool wizardMode)
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
Definition JsonParsing.h:12
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9