QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtQmlIntegration/QtQmlIntegration>
4
5#include "PlanManager.h"
6
7class Vehicle;
8
10{
11 Q_OBJECT
12 QML_ELEMENT
13 QML_UNCREATABLE("")
14public:
15 MissionManager(Vehicle* vehicle);
17
19 int currentIndex(void) const { return _currentMissionIndex; }
20
22 int lastCurrentIndex(void) const { return _lastCurrentIndex; }
23
27 void writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly);
28
31 void generateResumeMission(int resumeIndex);
32
33private slots:
34 void _mavlinkMessageReceived(const mavlink_message_t& message);
35
36private:
37 void _handleHighLatency(const mavlink_message_t& message);
38 void _handleHighLatency2(const mavlink_message_t& message);
39 void _handleMissionCurrent(const mavlink_message_t& message);
40 void _updateMissionIndex(int index);
41 void _handleHeartbeat(const mavlink_message_t& message);
42
43 int _cachedLastCurrentIndex;
44};
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....
Definition PlanManager.h:14
int _currentMissionIndex
int _lastCurrentIndex