3#include <QtQmlIntegration/QtQmlIntegration>
40 void _updateMissionIndex(
int index);
43 int _cachedLastCurrentIndex;
struct __mavlink_message mavlink_message_t
int lastCurrentIndex(void) const
Last current mission item reported while in Mission flight mode.
void generateResumeMission(int resumeIndex)
void writeArduPilotGuidedMissionItem(const QGeoCoordinate &gotoCoord, bool altChangeOnly)
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....