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
7Q_DECLARE_LOGGING_CATEGORY(MissionManagerLog)
8
9class Vehicle;
10
12{
13 Q_OBJECT
14 QML_ELEMENT
15 QML_UNCREATABLE("")
16public:
17 MissionManager(Vehicle* vehicle);
19
21 int currentIndex(void) const { return _currentMissionIndex; }
22
24 int lastCurrentIndex(void) const { return _lastCurrentIndex; }
25
29 void writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly);
30
33 void generateResumeMission(int resumeIndex);
34
35private slots:
36 void _mavlinkMessageReceived(const mavlink_message_t& message);
37
38private:
39 void _handleHighLatency(const mavlink_message_t& message);
40 void _handleHighLatency2(const mavlink_message_t& message);
41 void _handleMissionCurrent(const mavlink_message_t& message);
42 void _updateMissionIndex(int index);
43 void _handleHeartbeat(const mavlink_message_t& message);
44
45 int _cachedLastCurrentIndex;
46};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
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.
int _currentMissionIndex
int _lastCurrentIndex