QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LandingComplexItem.cc
Go to the documentation of this file.
2#include "QGCApplication.h"
3#include "JsonHelper.h"
4#include "MissionController.h"
7#include "SimpleMissionItem.h"
10#include "MissionItem.h"
11#include "Fact.h"
12#include "CameraSection.h"
13#include "Vehicle.h"
14#include "QGCLoggingCategory.h"
15
16QGC_LOGGING_CATEGORY(LandingComplexItemLog, "Plan.LandingComplexItem")
17
19 : ComplexMissionItem (masterController, flyView)
20{
21 _isIncomplete = false;
22
23 // The following is used to compress multiple recalc calls in a row to into a single call.
25 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&LandingComplexItem::_updateFlightPathSegmentsSignal));
26}
27
29{
31 // ArduPilot does not support camera commands
32 stopTakingVideo()->setRawValue(false);
33 stopTakingPhotos()->setRawValue(false);
34 }
35
38
39 connect(loiterRadius(), &Fact::valueChanged, this, &LandingComplexItem::_recalcFromRadiusChange);
40 connect(loiterClockwise(), &Fact::rawValueChanged, this, &LandingComplexItem::_recalcFromRadiusChange);
41
42 connect(useLoiterToAlt(), &Fact::rawValueChanged, this, &LandingComplexItem::_recalcFromApproachModeChange);
43
46
47 // 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
49
52
67
68 connect(stopTakingPhotos(), &Fact::valueChanged, this, &LandingComplexItem::_signalLastSequenceNumberChanged);
69 connect(stopTakingVideo(), &Fact::valueChanged, this, &LandingComplexItem::_signalLastSequenceNumberChanged);
70
77
80
84
92
94
95 connect(finalApproachAltitude(), &Fact::valueChanged, this, &LandingComplexItem::_updateFinalApproachCoodinateAltitudeFromFact);
96 connect(landingAltitude(), &Fact::valueChanged, this, &LandingComplexItem::_updateLandingCoodinateAltitudeFromFact);
97}
98
99void LandingComplexItem::setLandingHeadingToTakeoffHeading()
100{
102 if (takeoffMissionItem && takeoffMissionItem->specifiesCoordinate()) {
103 qreal heading = takeoffMissionItem->launchCoordinate().azimuthTo(takeoffMissionItem->coordinate());
104 landingHeading()->setRawValue(heading);
105 }
106}
107
109{
111}
112
113void LandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
114{
117 if (_landingCoordSet) {
119 } else {
122 _ignoreRecalcSignals = false;
123 _landingCoordSet = true;
125 emit landingCoordSetChanged(true);
126 }
127 }
128}
129
137
138QPointF LandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
139{
140 QPointF rotated;
141 double radians = (M_PI / 180.0) * angle;
142
143 rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
144 rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());
145
146 return rotated;
147}
148
150{
151 // Fixed:
152 // land
153 // heading
154 // distance
155 // radius
156 // Adjusted:
157 // final approach
158 // slope start
159
161 // These are our known values
162 double distance = landingDistance()->rawValue().toDouble();
163 double heading = landingHeading()->rawValue().toDouble();
164
165 // Heading is from slope start to land, hence +180
166 _slopeStartCoordinate = _landingCoordinate.atDistanceAndAzimuth(distance, heading + 180);
167
168 if (useLoiterToAlt()->rawValue().toBool()) {
169 double radius = loiterRadius()->rawValue().toDouble();
170
171 // Loiter coord is 90 degrees counter clockwise from tangent coord
172 _finalApproachCoordinate = _slopeStartCoordinate.atDistanceAndAzimuth(radius, heading - 180 + (_loiterClockwise()->rawValue().toBool() ? -90 : 90));
173 } else {
175 }
176
177 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
178
183 _ignoreRecalcSignals = false;
184 }
185}
186
187void LandingComplexItem::_recalcFromRadiusChange(void)
188{
189 // Fixed:
190 // land
191 // slope start
192 // distance
193 // radius
194 // heading
195 // Adjusted:
196 // loiter
197
199 // These are our known values
200 double radius = loiterRadius()->rawValue().toDouble();
201 double distance = landingDistance()->rawValue().toDouble();
202 double heading = landingHeading()->rawValue().toDouble();
203
204 double landToLoiterDistance = _landingCoordinate.distanceTo(_finalApproachCoordinate);
205 if (landToLoiterDistance < radius) {
206 // Degnenerate case: Move tangent to loiter point
208
209 double slopeStartHeading = _landingCoordinate.azimuthTo(_slopeStartCoordinate);
210
212 landingHeading()->setRawValue(slopeStartHeading);
214 _ignoreRecalcSignals = false;
215 } else {
216 double loiterDistance = qSqrt(qPow(radius, 2) + qPow(distance, 2));
217 double angleLoiterToTangent = qRadiansToDegrees(qAsin(radius/loiterDistance)) * (_loiterClockwise()->rawValue().toBool() ? -1 : 1);
218
219 _finalApproachCoordinate = _landingCoordinate.atDistanceAndAzimuth(loiterDistance, heading + 180 + angleLoiterToTangent);
220 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
221
224 _ignoreRecalcSignals = false;
225 }
226 }
227}
228
229void LandingComplexItem::_recalcFromApproachModeChange(void)
230{
231 // Fixed:
232 // land
233 // slope start
234 // heading
235 // distance
236 // Adjusted:
237 // final approach
238
240 if (useLoiterToAlt()->rawValue().toBool()) {
241 double radius = loiterRadius()->rawValue().toDouble();
242 double offsetAngle =
243 landingHeading()->rawValue().toDouble() - 180 +
244 (_loiterClockwise()->rawValue().toBool() ? -90 : 90);
245
247 _slopeStartCoordinate.atDistanceAndAzimuth(radius, offsetAngle);
248 } else {
250 }
251
252 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
253
257 _ignoreRecalcSignals = false;
258 }
259}
260
262{
263 // Fixed:
264 // land
265 // final approach
266 // radius
267 // Adjusted:
268 // heading
269 // distance
270 // slope start
271
273 double distance;
274
275 if (useLoiterToAlt()->rawValue().toBool()) {
276 // These are our known values
277 double radius = loiterRadius()->rawValue().toDouble();
278 double landToLoiterDistance = _landingCoordinate.distanceTo(_finalApproachCoordinate);
279 double landToLoiterHeading = _landingCoordinate.azimuthTo(_finalApproachCoordinate);
280
281 if (landToLoiterDistance < radius) {
282 // Degenerate case: tangent at loiter coordinate
285 } else {
286 // Calculate tangent point using circle geometry
287 double loiterToTangentAngle = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (_loiterClockwise()->rawValue().toBool() ? 1 : -1);
288 distance = qSqrt(qPow(landToLoiterDistance, 2) - qPow(radius, 2));
289 _slopeStartCoordinate = _landingCoordinate.atDistanceAndAzimuth(distance, landToLoiterHeading + loiterToTangentAngle);
290 }
291 } else {
294 }
295
296 double heading = _slopeStartCoordinate.azimuthTo(_landingCoordinate);
297
299 landingHeading()->setRawValue(heading);
300 landingDistance()->setRawValue(distance);
303 _ignoreRecalcSignals = false;
304 }
305}
306
308{
309 // Fixed items are:
310 // land start, loiter, land
311 // Optional items are:
312 // stop photos/video
313 return _sequenceNumber + 2 + (stopTakingPhotos()->rawValue().toBool() ? 2 : 0) + (stopTakingVideo()->rawValue().toBool() ? 1 : 0);
314}
315
316void LandingComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
317{
318 int seqNum = _sequenceNumber;
319
320 // IMPORTANT NOTE: Any changes here must also be taken into account in scanForItem
321
322 MissionItem* item = _createDoLandStartItem(seqNum++, missionItemParent);
323 items.append(item);
324
325 if (useDoChangeSpeed()->rawValue().toBool()) {
326 item = _createDoChangeSpeedItem(SPEED_TYPE_AIRSPEED, finalApproachSpeed()->rawValue().toDouble(), -1, seqNum++, missionItemParent);
327 items.append(item);
328 }
329
330 if (stopTakingPhotos()->rawValue().toBool()) {
331 CameraSection::appendStopTakingPhotos(items, seqNum, missionItemParent);
332 }
333
334 if (stopTakingVideo()->rawValue().toBool()) {
335 CameraSection::appendStopTakingVideo(items, seqNum, missionItemParent);
336 }
337
338 item = _createFinalApproachItem(seqNum++, missionItemParent);
339 items.append(item);
340
341 item = _createLandItem(seqNum++,
343 _landingCoordinate.latitude(), _landingCoordinate.longitude(), landingAltitude()->rawValue().toDouble(),
344 missionItemParent);
345 items.append(item);
346}
347
349{
350 auto doLandStartItem =
351 new MissionItem(seqNum, // sequence number
352 MAV_CMD_DO_LAND_START, // MAV_CMD
353 MAV_FRAME_MISSION, // MAV_FRAME
354 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 1-7
355 true, // autoContinue
356 false, // isCurrentItem
357 parent);
358
359 bool firmwareAllowsDoLandStartCoords =
362 MAV_CMD_DO_LAND_START)
364
365 // This allows skipping the coordinates for firmware that doesn't require
366 // them, keeping the flight plan simpler. The expression can be expanded to
367 // include any additional firmware versions where this is the case.
368 bool firmwareRequiresDoLandStartCoords =
371
372 if (firmwareAllowsDoLandStartCoords && firmwareRequiresDoLandStartCoords) {
373 doLandStartItem->setFrame(_altitudesAreRelative
374 ? MAV_FRAME_GLOBAL_RELATIVE_ALT
375 : MAV_FRAME_GLOBAL);
376
377 doLandStartItem->setParam5(_finalApproachCoordinate.latitude());
378 doLandStartItem->setParam6(_finalApproachCoordinate.longitude());
379 doLandStartItem->setParam7(
380 _finalApproachAltitude()->rawValue().toFloat());
381 }
382
383 return doLandStartItem;
384}
385
386MissionItem* LandingComplexItem::_createDoChangeSpeedItem(int speedType, int speedValue, int throttlePercentage, int seqNum, QObject* parent)
387{
388 return new MissionItem(seqNum++, // sequence number
389 MAV_CMD_DO_CHANGE_SPEED, // MAV_CMD
390 MAV_FRAME_MISSION, // MAV_FRAME
391 speedType, speedValue, throttlePercentage, // param 1-3
392 0.0, 0.0, 0.0, 0.0, // param 4-7
393 true, // autoContinue
394 false, // isCurrentItem
395 parent);
396}
397
399{
400 if (useLoiterToAlt()->rawValue().toBool()) {
401 return new MissionItem(seqNum,
402 MAV_CMD_NAV_LOITER_TO_ALT,
403 _altitudesAreRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
404 1.0, // Heading required = true
405 loiterRadius()->rawValue().toDouble() * (_loiterClockwise()->rawValue().toBool() ? 1.0 : -1.0),
406 0.0, // param 3 - unused
407 1.0, // Exit crosstrack - tangent of loiter to land point
408 _finalApproachCoordinate.latitude(),
409 _finalApproachCoordinate.longitude(),
410 _finalApproachAltitude()->rawValue().toFloat(),
411 true, // autoContinue
412 false, // isCurrentItem
413 parent);
414 } else {
415 return new MissionItem(seqNum,
416 MAV_CMD_NAV_WAYPOINT,
417 _altitudesAreRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
418 0, // No hold time
419 0, // Use default acceptance radius
420 0, // Pass through waypoint
421 qQNaN(), // Yaw not specified
422 _finalApproachCoordinate.latitude(),
423 _finalApproachCoordinate.longitude(),
424 _finalApproachAltitude()->rawValue().toFloat(),
425 true, // autoContinue
426 false, // isCurrentItem
427 parent);
428 }
429}
430
431bool LandingComplexItem::_scanForItems(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
432{
433 qCDebug(LandingComplexItemLog) << "VTOLLandingComplexItem::scanForItem count" << visualItems->count();
434
435 if (visualItems->count() < 3) {
436 return false;
437 }
438
439 // Start looking for the commands in reverse order from the end of the list
440 int startIndex = visualItems->count();
441 bool foundAny = false;
442
443 while (startIndex >= 0) {
444 if (_scanForItem(visualItems, startIndex, flyView, masterController, isLandItemFunc, createItemFunc)) {
445 foundAny = true;
446 } else {
447 startIndex--;
448 }
449 }
450
451 return foundAny;
452}
453
454bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, int& startIndex, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
455{
456 // A valid landing pattern is comprised of the follow commands in this order at the end of the item list:
457 // MAV_CMD_DO_LAND_START - required
458 // MAV_CMD_DO_CHANGE_SPEED - optional
459 // Stop taking photos sequence - optional
460 // Stop taking video sequence - optional
461 // MAV_CMD_NAV_LOITER_TO_ALT or MAV_CMD_NAV_WAYPOINT
462 // MAV_CMD_NAV_LAND or MAV_CMD_NAV_VTOL_LAND
463
464 int scanIndex = startIndex - 1;
465
466 if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
467 return false;
468 }
469 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex--);
470 if (!item) {
471 return false;
472 }
473 MissionItem& missionItemLand = item->missionItem();
474 if (!isLandItemFunc(missionItemLand)) {
475 return false;
476 }
477 MAV_FRAME landPointFrame = missionItemLand.frame();
478
479 if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
480 return false;
481 }
482 item = visualItems->value<SimpleMissionItem*>(scanIndex);
483 if (!item) {
484 return false;
485 }
486 bool useLoiterToAlt = true;
487 MissionItem& missionItemFinalApproach = item->missionItem();
488 if (missionItemFinalApproach.command() == MAV_CMD_NAV_LOITER_TO_ALT) {
489 if (missionItemFinalApproach.frame() != landPointFrame ||
491 // APM automatically changes the value of param1 to 1, so when sending a plan it will
492 // be 0, and when downloading it, the value will be 1
493 ? missionItemFinalApproach.param1() != 0.0 && missionItemFinalApproach.param1() != 1.0
494 : missionItemFinalApproach.param1() != 1.0) ||
495 missionItemFinalApproach.param3() != 0 || missionItemFinalApproach.param4() != 1.0) {
496 return false;
497 }
498 } else if (missionItemFinalApproach.command() == MAV_CMD_NAV_WAYPOINT) {
499 if (missionItemFinalApproach.frame() != landPointFrame ||
500 missionItemFinalApproach.param1() != 0 || missionItemFinalApproach.param2() != 0 || missionItemFinalApproach.param3() != 0 ||
501 (!masterController->managerVehicle()->apmFirmware() && !qIsNaN(missionItemFinalApproach.param4())) ||
502 qIsNaN(missionItemFinalApproach.param5()) || qIsNaN(missionItemFinalApproach.param6()) || qIsNaN(missionItemFinalApproach.param6())) {
503 return false;
504 }
505 useLoiterToAlt = false;
506 } else {
507 return false;
508 }
509
511 bool stopTakingVideo = CameraSection::scanStopTakingVideo(visualItems, scanIndex, false /* removeScannedItems */);
512 if (!stopTakingVideo) {
514 }
515
517 bool stopTakingPhotos = CameraSection::scanStopTakingPhotos(visualItems, scanIndex, false /* removeScannedItems */);
518 if (!stopTakingPhotos) {
520 }
521
522 scanIndex--;
523 bool useDoChangeSpeed = false;
524 double finalApproachSpeed = 0;
525 if (scanIndex >= 0 && scanIndex < visualItems->count()) {
526 item = visualItems->value<SimpleMissionItem*>(scanIndex);
527 if (item) {
528 MissionItem& missionItemChangeSpeed = item->missionItem();
529 if (missionItemChangeSpeed.command() == MAV_CMD_DO_CHANGE_SPEED &&
530 missionItemChangeSpeed.param1() == static_cast<double>(SPEED_TYPE_AIRSPEED) &&
531 missionItemChangeSpeed.param2() >= -2 &&
532 missionItemChangeSpeed.param3() == -1 &&
533 missionItemChangeSpeed.param4() == 0) {
534 useDoChangeSpeed = true;
535 finalApproachSpeed = missionItemChangeSpeed.param2();
536 }
537 }
538 }
539 if (!useDoChangeSpeed) {
540 scanIndex++;
541 }
542
543 scanIndex--;
544 if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
545 return false;
546 }
547 item = visualItems->value<SimpleMissionItem*>(scanIndex);
548 if (!item) {
549 return false;
550 }
551 MissionItem& missionItemDoLandStart = item->missionItem();
552 if (missionItemDoLandStart.command() != MAV_CMD_DO_LAND_START ||
553 missionItemDoLandStart.param1() != 0 || missionItemDoLandStart.param2() != 0 || missionItemDoLandStart.param3() != 0 || missionItemDoLandStart.param4() != 0 ||
554 missionItemDoLandStart.param5() != 0 || missionItemDoLandStart.param6() != 0 || missionItemDoLandStart.param7() != 0) {
555 return false;
556 }
557
558 // We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission.
559 int deleteCount = 3;
560 if (stopTakingPhotos) {
562 }
563 if (stopTakingVideo) {
565 }
566 if (useDoChangeSpeed) {
567 deleteCount++;
568 }
569 int firstItem = startIndex - deleteCount;
570 while (deleteCount--) {
571 visualItems->removeAt(firstItem)->deleteLater();
572 }
573
574 // Now stuff all the scanned information into the item
575
576 LandingComplexItem* complexItem = createItemFunc(masterController, flyView);
577
578 complexItem->_ignoreRecalcSignals = true;
579
580 complexItem->_altitudesAreRelative = landPointFrame == MAV_FRAME_GLOBAL_RELATIVE_ALT;
581 complexItem->setFinalApproachCoordinate(QGeoCoordinate(missionItemFinalApproach.param5(), missionItemFinalApproach.param6()));
582 complexItem->finalApproachAltitude()->setRawValue(missionItemFinalApproach.param7());
583 complexItem->useDoChangeSpeed()->setRawValue(useDoChangeSpeed);
584 complexItem->useLoiterToAlt()->setRawValue(useLoiterToAlt);
585
586 if (useDoChangeSpeed) {
587 complexItem->finalApproachSpeed()->setRawValue(finalApproachSpeed);
588 }
589 if (useLoiterToAlt) {
590 complexItem->loiterRadius()->setRawValue(qAbs(missionItemFinalApproach.param2()));
591 complexItem->loiterClockwise()->setRawValue(missionItemFinalApproach.param2() > 0);
592 }
593
594 complexItem->_landingCoordinate.setLatitude(missionItemLand.param5());
595 complexItem->_landingCoordinate.setLongitude(missionItemLand.param6());
596 complexItem->landingAltitude()->setRawValue(missionItemLand.param7());
597
598 complexItem->stopTakingPhotos()->setRawValue(stopTakingPhotos);
599 complexItem->stopTakingVideo()->setRawValue(stopTakingVideo);
600
601 complexItem->_landingCoordSet = true;
602
603 complexItem->_ignoreRecalcSignals = false;
604
605 complexItem->_recalcFromCoordinateChange();
606 complexItem->setDirty(false);
607
608 visualItems->insert(firstItem, complexItem);
609 startIndex = firstItem;
610
611 return true;
612}
613
615{
616 finalApproachAltitude()->setRawValue(newAltitude);
617}
618
623
625{
626 if (_dirty != dirty) {
627 _dirty = dirty;
628 emit dirtyChanged(_dirty);
629 }
630}
631
633{
634 setDirty(true);
635}
636
637void LandingComplexItem::setCoordinate(const QGeoCoordinate& coordinate) {
638 if (!_landingCoordSet) {
640 return;
641 }
642
643 // Move entire complex item, preserving heading and distance
646 _ignoreRecalcSignals = false;
648}
649
658
660{
661 return finalApproachAltitude()->rawValue().toDouble();
662}
663
665{
666 return finalApproachAltitude()->rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);
667}
668
670{
671 return landingAltitude()->rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);
672
673}
674
675void LandingComplexItem::_signalLastSequenceNumberChanged(void)
676{
678}
679
680void LandingComplexItem::_updateFinalApproachCoodinateAltitudeFromFact(void)
681{
682 _finalApproachCoordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
684}
685
686void LandingComplexItem::_updateLandingCoodinateAltitudeFromFact(void)
687{
688 _landingCoordinate.setAltitude(landingAltitude()->rawValue().toDouble());
690}
691
692double LandingComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
693{
694 return qMax(_finalApproachCoordinate.distanceTo(other),_landingCoordinate.distanceTo(other));
695}
696
698{
699 QJsonObject saveObject;
700
701 QGeoCoordinate coordinate;
702 QJsonValue jsonCoordinate;
703
705 coordinate.setAltitude(finalApproachAltitude()->rawValue().toDouble());
706 JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
707 saveObject[_jsonFinalApproachCoordinateKey] = jsonCoordinate;
708
709 saveObject[_jsonUseDoChangeSpeedKey] = useDoChangeSpeed()->rawValue().toBool();
710 saveObject[_jsonFinalApproachSpeedKey] = finalApproachSpeed()->rawValue().toDouble();
711
713 coordinate.setAltitude(landingAltitude()->rawValue().toDouble());
714 JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
715 saveObject[_jsonLandingCoordinateKey] = jsonCoordinate;
716
717 saveObject[_jsonLoiterRadiusKey] = loiterRadius()->rawValue().toDouble();
718 saveObject[_jsonStopTakingPhotosKey] = stopTakingPhotos()->rawValue().toBool();
719 saveObject[_jsonStopTakingVideoKey] = stopTakingVideo()->rawValue().toBool();
720 saveObject[_jsonLoiterClockwiseKey] = loiterClockwise()->rawValue().toBool();
721 saveObject[_jsonUseLoiterToAltKey] = useLoiterToAlt()->rawValue().toBool();
723
724 return saveObject;
725}
726
727bool LandingComplexItem::_load(const QJsonObject& complexObject, int sequenceNumber, const QString& jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString& errorString)
728{
729 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
730 { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
731 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
732 { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
733 { _jsonDeprecatedLoiterCoordinateKey, QJsonValue::Array, false }, // Loiter changed to Final Approach
734 { _jsonFinalApproachCoordinateKey, QJsonValue::Array, false },
735 { _jsonUseDoChangeSpeedKey, QJsonValue::Bool, false },
736 { _jsonFinalApproachSpeedKey, QJsonValue::Double, false },
737 { _jsonLoiterRadiusKey, QJsonValue::Double, true },
738 { _jsonLoiterClockwiseKey, QJsonValue::Bool, true },
739 { _jsonLandingCoordinateKey, QJsonValue::Array, true },
740 { _jsonStopTakingPhotosKey, QJsonValue::Bool, false },
741 { _jsonStopTakingVideoKey, QJsonValue::Bool, false },
742 { _jsonUseLoiterToAltKey, QJsonValue::Bool, false },
743 };
744 if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
745 return false;
746 }
747
748 if (!complexObject.contains(_jsonDeprecatedLoiterCoordinateKey) && !complexObject.contains(_jsonFinalApproachCoordinateKey)) {
749 QList<JsonHelper::KeyValidateInfo> finalApproachKeyInfoList = {
750 { _jsonFinalApproachCoordinateKey, QJsonValue::Array, true },
751 };
752 if (!JsonHelper::validateKeys(complexObject, finalApproachKeyInfoList, errorString)) {
753 return false;
754 }
755 }
756
757 QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
758 QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
759 if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
760 errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(QCoreApplication::applicationName()).arg(itemType).arg(complexType);
761 return false;
762 }
763
765
767
768 if (useDeprecatedRelAltKeys) {
769 QList<JsonHelper::KeyValidateInfo> v1KeyInfoList = {
770 { _jsonDeprecatedLoiterAltitudeRelativeKey, QJsonValue::Bool, true },
771 { _jsonDeprecatedLandingAltitudeRelativeKey, QJsonValue::Bool, true },
772 };
773 if (!JsonHelper::validateKeys(complexObject, v1KeyInfoList, errorString)) {
774 return false;
775 }
776
777 bool loiterAltitudeRelative = complexObject[_jsonDeprecatedLoiterAltitudeRelativeKey].toBool();
778 bool landingAltitudeRelative = complexObject[_jsonDeprecatedLandingAltitudeRelativeKey].toBool();
779 if (loiterAltitudeRelative != landingAltitudeRelative) {
780 qgcApp()->showAppMessage(tr("Fixed Wing Landing Pattern: "
781 "Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
782 "Both have been set to relative altitude. Be sure to adjust/check your plan prior to flight."));
784 } else {
785 _altitudesAreRelative = loiterAltitudeRelative;
786 }
787 } else {
788 QList<JsonHelper::KeyValidateInfo> v2KeyInfoList = {
789 { _jsonAltitudesAreRelativeKey, QJsonValue::Bool, true },
790 };
791 if (!JsonHelper::validateKeys(complexObject, v2KeyInfoList, errorString)) {
792 _ignoreRecalcSignals = false;
793 return false;
794 }
795 _altitudesAreRelative = complexObject[_jsonAltitudesAreRelativeKey].toBool();
796 }
797
798 QGeoCoordinate coordinate;
800 if (!JsonHelper::loadGeoCoordinate(complexObject[finalApproachKey], true /* altitudeRequired */, coordinate, errorString)) {
801 return false;
802 }
804 finalApproachAltitude()->setRawValue(coordinate.altitude());
805
806 useDoChangeSpeed()->setRawValue(complexObject[_jsonUseDoChangeSpeedKey].toBool(false));
807 finalApproachSpeed()->setRawValue(complexObject.contains(_jsonFinalApproachSpeedKey)
808 ? complexObject[_jsonFinalApproachSpeedKey].toDouble()
809 : finalApproachSpeed()->rawDefaultValue());
810
811 if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
812 return false;
813 }
815 landingAltitude()->setRawValue(coordinate.altitude());
816
817 loiterRadius()->setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble());
818 loiterClockwise()->setRawValue(complexObject[_jsonLoiterClockwiseKey].toBool());
819 useLoiterToAlt()->setRawValue(complexObject[_jsonUseLoiterToAltKey].toBool(true));
820 stopTakingPhotos()->setRawValue(complexObject[_jsonStopTakingPhotosKey].toBool(false));
821 stopTakingVideo()->setRawValue(complexObject[_jsonStopTakingVideoKey].toBool(false));
822
824
825 _landingCoordSet = true;
826 _ignoreRecalcSignals = false;
827
829 // These will kick off terrain query
832
833 return true;
834}
835
#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)
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 ...
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)
bool apmFirmware() const
Definition Vehicle.h:496
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:3646
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)
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)
QGCMAVLink::VehicleClass_t _previousVTOLMode
Generic == unknown.
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
PlanMasterController * masterController(void)
void wizardModeChanged(bool wizardMode)
constexpr const char * jsonVersionKey
Definition JsonHelper.h:109
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