3#include <QtCore/QObject>
4#include <QtCore/QString>
5#include <QtCore/QLoggingCategory>
6#include <QtPositioning/QGeoCoordinate>
7#include <QtQmlIntegration/QtQmlIntegration>
24 Q_MOC_INCLUDE(
"PlanMasterController.h")
41 Q_PROPERTY(
bool homePosition READ homePosition
CONSTANT)
132 virtual bool dirty (
void)
const = 0;
174 virtual void save(QJsonArray& missionItems) = 0;
280 void _updateTerrainAltitude (
void);
281 void _reallyUpdateTerrainAltitude (
void);
282 void _terrainDataReceived (
bool success, QList<double> heights);
285 void _commonInit(
void);
287 QTimer _updateTerrainTimer;
290 double _lastLatTerrainQuery = 0;
291 double _lastLonTerrainQuery = 0;
Master controller for mission, fence, rally.
static constexpr const VehicleClass_t VehicleClassGeneric
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be o...
virtual int lastSequenceNumber(void) const =0
virtual bool dirty(void) const =0
virtual QString abbreviation(void) const =0
void _amslExitAltChanged(void)
void setIsCurrentItem(bool isCurrentItem)
void setDistanceFromStart(double distanceFromStart)
void setHasCurrentChildItem(bool hasCurrentChildItem)
PlanMasterController * _masterController
virtual QString mapVisualQML(void) const =0
void specifiedVehicleYawChanged(void)
virtual void setCoordinate(const QGeoCoordinate &coordinate)=0
VisualMissionItem * _parentItem
bool _homePositionSpecialCase
true: This item is being used as a ui home position indicator
void distanceChanged(double distance)
virtual int sequenceNumber(void) const =0
void _setBoundingCube(QGCGeoBoundingCube bc)
void setTerrainCollision(bool terrainCollision)
virtual void applyNewAltitude(double newAltitude)=0
Adjust the altitude of the item if appropriate to the new altitude.
void abbreviationChanged(void)
void setAltDifference(double altDifference)
void setMissionVehicleYaw(double vehicleYaw)
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
bool _hasCurrentChildItem
virtual bool isTakeoffItem(void) const
virtual bool isStandaloneCoordinate(void) const =0
QmlObjectListModel _childItems
This is used to reference any subsequent mission items which do not specify a coordinate.
bool hasCurrentChildItem(void) const
void amslExitAltChanged(double alt)
double altDifference(void) const
QString _editorQml
Qml resource for editing item.
virtual double amslExitAlt(void) const =0
void setParentItem(VisualMissionItem *parentItem)
void terrainAltitudeChanged(double terrainAltitude)
void isCurrentItemChanged(bool isCurrentItem)
void terrainCollisionChanged(bool terrainCollision)
void azimuthChanged(double azimuth)
void setWizardMode(bool wizardMode)
void specifiesAltitudeOnlyChanged(void)
bool isCurrentItem(void) const
void lastSequenceNumberChanged(int sequenceNumber)
void commandNameChanged(void)
double _distanceFromStart
Flight path cumalative horizontal distance from home point to this item.
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
double altPercent(void) const
void specifiesCoordinateChanged(void)
void coordinateChanged(const QGeoCoordinate &coordinate)
void setSimpleFlighPathSegment(FlightPathSegment *segment)
virtual double specifiedGimbalPitch(void)=0
void readyForSaveStateChanged(void)
double terrainPercent(void) const
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 specifiedVehicleYaw(void)
virtual double specifiedFlightSpeed(void)=0
double missionVehicleYaw(void) const
FlightPathSegment * simpleFlightPathSegment(void)
void commandDescriptionChanged(void)
void missionGimbalYawChanged(double missionGimbalYaw)
virtual double amslEntryAlt(void) const =0
void isSimpleItemChanged(bool isSimpleItem)
void setAltPercent(double altPercent)
Vehicle * _controllerVehicle
virtual ReadyForSaveState readyForSaveState(void) const
MissionController * _missionController
void specifiedGimbalYawChanged(void)
double distance(void) const
void isStandaloneCoordinateChanged(void)
void altDifferenceChanged(double altDifference)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
void setTerrainPercent(double terrainPercent)
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus)
double _terrainAltitude
Altitude of terrain at coordinate position, NaN for not known.
double _terrainPercent
Percent of terrain altitude for coordinate.
double _altDifference
Difference in altitude from previous waypoint.
void parentItemChanged(VisualMissionItem *parentItem)
double distanceFromStart(void) const
bool _wizardMode
true: Item editor is showing wizard completion panel
void exitCoordinateSameAsEntryChanged(bool exitCoordinateSameAsEntry)
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
virtual bool isSurveyItem(void) const
FlightPathSegment * _simpleFlightPathSegment
The simple item flight segment (if any) which starts with this visual item.
void isLandCommandChanged(void)
double missionGimbalYaw(void) const
bool wizardMode(void) const
void isTakeoffItemChanged(bool isTakeoffItem)
virtual QGeoCoordinate coordinate(void) const =0
void boundingCubeChanged(void)
virtual bool specifiesAltitudeOnly(void) const =0
void previousVTOLModeChanged(void)
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)
void sequenceNumberChanged(int sequenceNumber)
QGCMAVLink::VehicleClass_t _previousVTOLMode
Generic == unknown.
virtual void setDirty(bool dirty)=0
virtual bool isSimpleItem(void) const =0
double _distance
Distance to previous waypoint.
QmlObjectListModel * childItems(void)
virtual bool exitCoordinateSameAsEntry(void) const =0
virtual double additionalTimeDelay(void) const =0
virtual bool specifiesCoordinate(void) const =0
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void setHomePositionSpecialCase(bool homePositionSpecialCase)
void setAzimuth(double azimuth)
QGCGeoBoundingCube _boundingCube
The bounding "cube" of this element.
void additionalTimeDelayChanged(void)
bool _terrainCollision
true: item collides with terrain
virtual QString commandDescription(void) const =0
const VisualMissionItem & operator=(const VisualMissionItem &other)
PlanMasterController * masterController(void)
void wizardModeChanged(bool wizardMode)
void hasCurrentChildItemChanged(bool hasCurrentChildItem)
void altPercentChanged(double altPercent)
double _altPercent
Percent of total altitude change in mission.
virtual void save(QJsonArray &missionItems)=0
virtual QGeoCoordinate exitCoordinate(void) const =0
VisualMissionItem * parentItem(void)
double azimuth(void) const
virtual QGeoCoordinate entryCoordinate(void) const =0
bool terrainCollision(void) const
bool homePosition READ homePosition CONSTANT(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) 1(double amslEntryAlt READ amslEntryAlt NOTIFY amslEntryAltChanged) 1(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) 1(QGeoCoordinate entryCoordinate READ entryCoordinate NOTIFY entryCoordinateChanged) 1(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged) 1(double amslExitAlt READ amslExitAlt NOTIFY amslExitAltChanged) 1(bool exitCoordinateSameAsEntry READ exitCoordinateSameAsEntry NOTIFY exitCoordinateSameAsEntryChanged) 1(QString commandDescription READ commandDescription NOTIFY commandDescriptionChanged) 1(QString commandName READ commandName NOTIFY commandNameChanged) 1(QString abbreviation READ abbreviation NOTIFY abbreviationChanged) 1(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) 1(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged) 1(bool hasCurrentChildItem READ hasCurrentChildItem WRITE setHasCurrentChildItem NOTIFY hasCurrentChildItemChanged) 1(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged) 1(int lastSequenceNumber READ lastSequenceNumber NOTIFY lastSequenceNumberChanged) 1(bool specifiesCoordinate READ specifiesCoordinate NOTIFY specifiesCoordinateChanged) 1(bool isStandaloneCoordinate READ isStandaloneCoordinate NOTIFY isStandaloneCoordinateChanged) 1(bool specifiesAltitudeOnly READ specifiesAltitudeOnly NOTIFY specifiesAltitudeOnlyChanged) 1(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) 1(bool isTakeoffItem READ isTakeoffItem NOTIFY isTakeoffItemChanged) 1(bool isLandCommand READ isLandCommand NOTIFY isLandCommandChanged) 1(bool isSurveyItem READ isSurveyItem) 1(QString editorQml MEMBER _editorQml CONSTANT) 1(QString mapVisualQML READ mapVisualQML CONSTANT) 1(double specifiedFlightSpeed READ specifiedFlightSpeed NOTIFY specifiedFlightSpeedChanged) 1(double specifiedGimbalYaw READ specifiedGimbalYaw NOTIFY specifiedGimbalYawChanged) 1(double specifiedGimbalPitch READ specifiedGimbalPitch NOTIFY specifiedGimbalPitchChanged) 1(double specifiedVehicleYaw READ specifiedVehicleYaw NOTIFY specifiedVehicleYawChanged) 1(double missionGimbalYaw READ missionGimbalYaw NOTIFY missionGimbalYawChanged) 1(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) 1(bool flyView READ flyView CONSTANT) 1(bool wizardMode READ wizardMode WRITE setWizardMode NOTIFY wizardModeChanged) 1(int previousVTOLMode MEMBER _previousVTOLMode NOTIFY previousVTOLModeChanged) 1(PlanMasterController *masterController READ masterController CONSTANT) 1(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged) 1(VisualMissionItem *parentItem READ parentItem WRITE setParentItem NOTIFY parentItemChanged) 1(QmlObjectListModel *childItems READ childItems CONSTANT) 1(QGCGeoBoundingCube *boundingCube READ boundingCube NOTIFY boundingCubeChanged) 1(double altDifference READ altDifference WRITE setAltDifference NOTIFY altDifferenceChanged) 1(double altPercent READ altPercent WRITE setAltPercent NOTIFY altPercentChanged) 1(double terrainPercent READ terrainPercent WRITE setTerrainPercent NOTIFY terrainPercentChanged) 1(bool terrainCollision READ terrainCollision WRITE setTerrainCollision NOTIFY terrainCollisionChanged) 1(double azimuth READ azimuth WRITE setAzimuth NOTIFY azimuthChanged) 1(double distance READ distance WRITE setDistance NOTIFY distanceChanged) 1(double distanceFromStart READ distanceFromStart WRITE setDistanceFromStart NOTIFY distanceFromStartChanged) bool homePosition(void) const
< true: This item is being used as a home position indicator
double terrainAltitude(void) const
void missionVehicleYawChanged(double missionVehicleYaw)
virtual double editableAlt(void) const =0
double _azimuth
Azimuth to previous waypoint.
double _missionVehicleYaw
void terrainPercentChanged(double terrainPercent)
void distanceFromStartChanged(double distanceFromStart)