QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PlanManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QTimer>
5#include <QtCore/QLoggingCategory>
6
7#include "MissionItem.h"
8#include "QGCMAVLink.h"
9
10class Vehicle;
11
12Q_DECLARE_LOGGING_CATEGORY(PlanManagerLog)
13
14
16class PlanManager : public QObject
17{
18 Q_OBJECT
19
20public:
21 PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType);
23
24 bool inProgress(void) const;
25 const QList<MissionItem*>& missionItems(void) { return _missionItems; }
26
28 int currentIndex(void) const { return _currentMissionIndex; }
29
31 int lastCurrentIndex(void) const { return _lastCurrentIndex; }
32
35 void loadFromVehicle(void);
36
41 void writeMissionItems(const QList<MissionItem*>& missionItems);
42
45 void removeAll(void);
46
59
60 // These values are public so the unit test can set appropriate signal wait times
61 // When passively waiting for a mission process, use a longer timeout.
62 static constexpr int _ackTimeoutMilliseconds = 1500;
63 // When actively retrying to request mission items, use a shorter timeout instead.
64 static constexpr int _retryTimeoutMilliseconds = 250;
65 static constexpr int _maxRetryCount = 5;
66
68 static constexpr int kTestAckTimeoutMs = 50;
69
70signals:
71 void newMissionItemsAvailable (bool removeAllRequested);
72 void inProgressChanged (bool inProgress);
73 void error (int errorCode, const QString& errorMsg);
74 void currentIndexChanged (int currentIndex);
75 void lastCurrentIndexChanged (int lastCurrentIndex);
76 void progressPctChanged (double progressPercentPct);
78 void sendComplete (bool error);
79 void resumeMissionReady (void);
81
82private slots:
83 void _mavlinkMessageReceived(const mavlink_message_t& message);
84 void _ackTimeout(void);
85
86protected:
95
96 typedef enum {
100 TransactionRemoveAll
101 } TransactionType_t;
102
103 void _startAckTimeout(AckType_t ack);
104 bool _checkForExpectedAck(AckType_t receivedAck);
105 void _readTransactionComplete(void);
106 void _handleMissionCount(const mavlink_message_t& message);
107 void _handleMissionItem(const mavlink_message_t& message);
108 void _handleMissionRequest(const mavlink_message_t& message);
109 void _handleMissionAck(const mavlink_message_t& message);
110 void _requestNextMissionItem(void);
111 void _clearMissionItems(void);
112 void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
113 QString _ackTypeToString(AckType_t ackType);
114 QString _missionResultToString(MAV_MISSION_RESULT result);
115 void _finishTransaction(bool success, bool apmGuidedItemWrite = false);
116 void _requestList(void);
117 void _writeMissionCount(void);
118 void _writeMissionItemsWorker(void);
119 void _clearAndDeleteMissionItems(void);
120 void _clearAndDeleteWriteMissionItems(void);
121 QString _lastMissionReqestString(MAV_MISSION_RESULT result);
122 void _removeAllWorker(void);
123 void _connectToMavlink(void);
124 void _disconnectFromMavlink(void);
125 QString _planTypeString(void);
126
127protected:
128 Vehicle* _vehicle = nullptr;
129 MAV_MISSION_TYPE _planType;
130
131 QTimer* _ackTimeoutTimer = nullptr;
134
141
142 QList<MissionItem*> _missionItems;
143 QList<MissionItem*> _writeMissionItems;
146
147private:
148 void _setTransactionInProgress(TransactionType_t type);
149};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
Error error
struct __mavlink_message mavlink_message_t
int _currentMissionIndex
bool _resumeMission
QList< MissionItem * > _missionItems
Set of mission items on vehicle.
void resumeMissionUploadFail(void)
QList< int > _itemIndicesToRead
List of mission items which still need to be requested from vehicle.
int _lastMissionRequest
Index of item last requested by MISSION_REQUEST.
TransactionType_t _transactionInProgress
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
Definition PlanManager.h:28
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void sendComplete(bool error)
void resumeMissionReady(void)
int lastCurrentIndex(void) const
Last current mission item reported while in Mission flight mode.
Definition PlanManager.h:31
@ AckTimeoutError
Timed out waiting for response from vehicle.
Definition PlanManager.h:50
@ ItemMismatchError
Vehicle returned item with seq # different than requested.
Definition PlanManager.h:53
@ MaxRetryExceeded
Retry failed.
Definition PlanManager.h:56
@ MissionTypeMismatch
MAV_MISSION_TYPE does not match _planType.
Definition PlanManager.h:57
@ ProtocolError
Incorrect protocol sequence from vehicle.
Definition PlanManager.h:51
@ MissingRequestsError
Vehicle did not request all items during write sequence.
Definition PlanManager.h:55
@ RequestRangeError
Vehicle requested item out of range.
Definition PlanManager.h:52
@ VehicleAckError
Vehicle returned error in ack.
Definition PlanManager.h:54
int _missionItemCountToRead
Count of all mission items to read.
int _lastCurrentIndex
void newMissionItemsAvailable(bool removeAllRequested)
MAV_MISSION_TYPE _planType
AckType_t _expectedAck
void removeAllComplete(bool error)
QList< int > _itemIndicesToWrite
List of mission items which still need to be written to vehicle.
void inProgressChanged(bool inProgress)
QList< MissionItem * > _writeMissionItems
Set of mission items currently being written to vehicle.
void progressPctChanged(double progressPercentPct)
@ AckMissionItem
MISSION_ITEM expected.
Definition PlanManager.h:90
@ AckMissionRequest
MISSION_REQUEST is expected, or MISSION_ACK to end sequence.
Definition PlanManager.h:91
@ AckMissionCount
MISSION_COUNT message expected.
Definition PlanManager.h:89
@ AckMissionClearAll
MISSION_CLEAR_ALL sent, MISSION_ACK is expected.
Definition PlanManager.h:92
@ AckNone
State machine is idle.
Definition PlanManager.h:88
@ AckGuidedItem
MISSION_ACK expected in response to ArduPilot guided mode single item send.
Definition PlanManager.h:93
const QList< MissionItem * > & missionItems(void)
Definition PlanManager.h:25
void error(int errorCode, const QString &errorMsg)