3#include <QtCore/QObject>
4#include <QtCore/QString>
5#include <QtPositioning/QGeoCoordinate>
6#include <QtQmlIntegration/QtQmlIntegration>
26 Q_MOC_INCLUDE(
"PlanMasterController.h")
67 Q_PROPERTY(QString editorQml MEMBER
_editorQml CONSTANT)
136 virtual bool dirty (
void)
const = 0;
178 virtual void save(QJsonArray& missionItems) = 0;
286 void _updateTerrainAltitude (
void);
287 void _reallyUpdateTerrainAltitude (
void);
288 void _terrainDataReceived (
bool success, QList<double> heights);
291 void _commonInit(
void);
293 QTimer _updateTerrainTimer;
296 double _lastLatTerrainQuery = 0;
297 double _lastLonTerrainQuery = 0;
Master controller for mission, fence, rally.
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)
bool terrainQueryFailed(void) const
void coordinateChanged(const QGeoCoordinate &coordinate)
QGCMAVLinkTypes::VehicleClass_t _previousVTOLMode
Generic == unknown.
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
bool homePosition(void) const
< Flight path cumalative horizontal distance from home point to this item
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)
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)
bool _terrainQueryFailed
true: Last terrain query failed
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)
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
virtual void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus)
VisualMissionItem * parentItem(void)
double azimuth(void) const
virtual QGeoCoordinate entryCoordinate(void) const =0
bool terrainCollision(void) const
double terrainAltitude(void) const
void missionVehicleYawChanged(double missionVehicleYaw)
virtual double editableAlt(void) const =0
void terrainQueryFailedChanged(bool terrainQueryFailed)
double _azimuth
Azimuth to previous waypoint.
double _missionVehicleYaw
void terrainPercentChanged(double terrainPercent)
void distanceFromStartChanged(double distanceFromStart)
static constexpr VehicleClass_t VehicleClassGeneric