23 _isIncomplete =
false;
143 double radians = (M_PI / 180.0) * angle;
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());
189void LandingComplexItem::_recalcFromRadiusChange(
void)
207 if (landToLoiterDistance < radius) {
218 double loiterDistance = qSqrt(qPow(radius, 2) + qPow(
distance, 2));
219 double angleLoiterToTangent = qRadiansToDegrees(qAsin(radius/loiterDistance)) * (
_loiterClockwise()->
rawValue().toBool() ? -1 : 1);
231void LandingComplexItem::_recalcFromApproachModeChange(
void)
283 if (landToLoiterDistance < radius) {
289 double loiterToTangentAngle = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (
_loiterClockwise()->
rawValue().toBool() ? 1 : -1);
290 distance = qSqrt(qPow(landToLoiterDistance, 2) - qPow(radius, 2));
352 auto doLandStartItem =
354 MAV_CMD_DO_LAND_START,
356 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
361 bool firmwareAllowsDoLandStartCoords =
364 MAV_CMD_DO_LAND_START)
370 bool firmwareRequiresDoLandStartCoords =
374 if (firmwareAllowsDoLandStartCoords && firmwareRequiresDoLandStartCoords) {
376 ? MAV_FRAME_GLOBAL_RELATIVE_ALT
381 doLandStartItem->setParam7(
385 return doLandStartItem;
391 MAV_CMD_DO_CHANGE_SPEED,
393 speedType, speedValue, throttlePercentage,
404 MAV_CMD_NAV_LOITER_TO_ALT,
418 MAV_CMD_NAV_WAYPOINT,
435 qCDebug(LandingComplexItemLog) <<
"VTOLLandingComplexItem::scanForItem count" << visualItems->
count();
437 if (visualItems->
count() < 3) {
442 int startIndex = visualItems->
count();
443 bool foundAny =
false;
445 while (startIndex >= 0) {
466 int scanIndex = startIndex - 1;
468 if (scanIndex < 0 || scanIndex > visualItems->
count() - 1) {
476 if (!isLandItemFunc(missionItemLand)) {
479 MAV_FRAME landPointFrame = missionItemLand.
frame();
481 if (scanIndex < 0 || scanIndex > visualItems->
count() - 1) {
490 if (missionItemFinalApproach.
command() == MAV_CMD_NAV_LOITER_TO_ALT) {
491 if (missionItemFinalApproach.
frame() != landPointFrame ||
495 ? missionItemFinalApproach.
param1() != 0.0 && missionItemFinalApproach.
param1() != 1.0
496 : missionItemFinalApproach.
param1() != 1.0) ||
497 missionItemFinalApproach.
param3() != 0 || missionItemFinalApproach.
param4() != 1.0) {
500 }
else if (missionItemFinalApproach.
command() == MAV_CMD_NAV_WAYPOINT) {
501 if (missionItemFinalApproach.
frame() != landPointFrame ||
502 missionItemFinalApproach.
param1() != 0 || missionItemFinalApproach.
param2() != 0 || missionItemFinalApproach.
param3() != 0 ||
504 qIsNaN(missionItemFinalApproach.
param5()) || qIsNaN(missionItemFinalApproach.
param6()) || qIsNaN(missionItemFinalApproach.
param6())) {
527 if (scanIndex >= 0 && scanIndex < visualItems->count()) {
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) {
546 if (scanIndex < 0 || scanIndex > visualItems->
count() - 1) {
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) {
571 int firstItem = startIndex - deleteCount;
572 while (deleteCount--) {
573 visualItems->
removeAt(firstItem)->deleteLater();
610 visualItems->
insert(firstItem, complexItem);
611 startIndex = firstItem;
677void LandingComplexItem::_signalLastSequenceNumberChanged(
void)
682void LandingComplexItem::_updateFinalApproachCoodinateAltitudeFromFact(
void)
688void LandingComplexItem::_updateLandingCoodinateAltitudeFromFact(
void)
701 QJsonObject saveObject;
704 QJsonValue jsonCoordinate;
731 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
751 QList<JsonParsing::KeyValidateInfo> finalApproachKeyInfoList = {
762 errorString = tr(
"%1 does not support loading this complex mission item type: %2:%3").arg(QCoreApplication::applicationName()).arg(itemType).arg(complexType);
770 if (useDeprecatedRelAltKeys) {
771 QList<JsonParsing::KeyValidateInfo> v1KeyInfoList = {
781 if (loiterAltitudeRelative != landingAltitudeRelative) {
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."));
790 QList<JsonParsing::KeyValidateInfo> v2KeyInfoList = {
#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
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
Q_INVOKABLE void setLandingHeadingToTakeoffHeading()
const Fact * landingAltitude(void) const
bool _altitudesAreRelative
virtual void _updateFlightPathSegmentsDontCallDirectly(void)=0
void landingCoordSetChanged(bool landingCoordSet)
bool _ignoreRecalcSignals
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
double param5(void) const
double param7(void) const
MAV_FRAME frame(void) const
double param3(void) const
double param6(void) const
double param1(void) const
double param4(void) const
double param2(void) const
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
Vehicle * managerVehicle(void)
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
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
void _amslExitAltChanged(void)
PlanMasterController * _masterController
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)
Vehicle * _controllerVehicle
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
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.