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 "MissionItem.h"
6#include "QGCMAVLink.h"
7
8class Vehicle;
9
12
13class PlanManager : public QObject
14{
15 Q_OBJECT
16
17public:
18 PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType);
20
21 bool inProgress(void) const;
22 const QList<MissionItem*>& missionItems(void) { return _missionItems; }
23
25 int currentIndex(void) const { return _currentMissionIndex; }
26
28 int lastCurrentIndex(void) const { return _lastCurrentIndex; }
29
32 void loadFromVehicle(void);
33
38 void writeMissionItems(const QList<MissionItem*>& missionItems);
39
42 void removeAll(void);
43
56
57 // These values are public so the unit test can set appropriate signal wait times
58 // When passively waiting for a mission process, use a longer timeout.
59 static constexpr int _ackTimeoutMilliseconds = 1500;
60 // When actively retrying to request mission items, use a shorter timeout instead.
61 static constexpr int _retryTimeoutMilliseconds = 250;
62 static constexpr int _maxRetryCount = 5;
63
65 static constexpr int kTestAckTimeoutMs = 50;
66
67signals:
68 void newMissionItemsAvailable (bool removeAllRequested);
70 void error (int errorCode, const QString& errorMsg);
73 void progressPctChanged (double progressPercentPct);
75 void sendComplete (bool error);
76 void resumeMissionReady (void);
78
79private slots:
80 void _mavlinkMessageReceived(const mavlink_message_t& message);
81 void _ackTimeout(void);
82
83protected:
92
99
100 void _startAckTimeout(AckType_t ack);
101 bool _checkForExpectedAck(AckType_t receivedAck);
102 void _readTransactionComplete(void);
103 void _handleMissionCount(const mavlink_message_t& message);
104 void _handleMissionItem(const mavlink_message_t& message);
105 void _handleMissionRequest(const mavlink_message_t& message);
106 void _handleMissionAck(const mavlink_message_t& message);
107 void _requestNextMissionItem(void);
108 void _clearMissionItems(void);
109 void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
110 QString _ackTypeToString(AckType_t ackType);
111 QString _missionResultToString(MAV_MISSION_RESULT result);
112 void _finishTransaction(bool success, bool apmGuidedItemWrite = false);
113 void _requestList(void);
114 void _writeMissionCount(void);
115 void _writeMissionItemsWorker(void);
118 QString _lastMissionReqestString(MAV_MISSION_RESULT result);
119 void _removeAllWorker(void);
120 void _connectToMavlink(void);
121 void _disconnectFromMavlink(void);
122 QString _planTypeString(void);
123
124protected:
125 Vehicle* _vehicle = nullptr;
126 MAV_MISSION_TYPE _planType;
127
128 QTimer* _ackTimeoutTimer = nullptr;
131
138
139 QList<MissionItem*> _missionItems;
140 QList<MissionItem*> _writeMissionItems;
143
144private:
145 void _setTransactionInProgress(TransactionType_t type);
146};
Error error
struct __mavlink_message mavlink_message_t
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....
Definition PlanManager.h:14
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
bool _checkForExpectedAck(AckType_t receivedAck)
void _handleMissionRequest(const mavlink_message_t &message)
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
Definition PlanManager.h:25
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void sendComplete(bool error)
void _handleMissionItem(const mavlink_message_t &message)
void resumeMissionReady(void)
void removeAll(void)
int lastCurrentIndex(void) const
Last current mission item reported while in Mission flight mode.
Definition PlanManager.h:28
void _clearAndDeleteWriteMissionItems(void)
QTimer * _ackTimeoutTimer
ErrorCode_t
Error codes returned in error signal.
Definition PlanManager.h:45
@ AckTimeoutError
Timed out waiting for response from vehicle.
Definition PlanManager.h:47
@ ItemMismatchError
Vehicle returned item with seq # different than requested.
Definition PlanManager.h:50
@ MaxRetryExceeded
Retry failed.
Definition PlanManager.h:53
@ MissionTypeMismatch
MAV_MISSION_TYPE does not match _planType.
Definition PlanManager.h:54
@ ProtocolError
Incorrect protocol sequence from vehicle.
Definition PlanManager.h:48
@ MissingRequestsError
Vehicle did not request all items during write sequence.
Definition PlanManager.h:52
@ RequestRangeError
Vehicle requested item out of range.
Definition PlanManager.h:49
@ VehicleAckError
Vehicle returned error in ack.
Definition PlanManager.h:51
int _missionItemCountToRead
Count of all mission items to read.
static constexpr int kTestAckTimeoutMs
Ack timeout used in unit tests (much shorter for faster tests)
Definition PlanManager.h:65
int _lastCurrentIndex
void newMissionItemsAvailable(bool removeAllRequested)
MAV_MISSION_TYPE _planType
QString _missionResultToString(MAV_MISSION_RESULT result)
QString _lastMissionReqestString(MAV_MISSION_RESULT result)
static constexpr int _maxRetryCount
Definition PlanManager.h:62
void _finishTransaction(bool success, bool apmGuidedItemWrite=false)
void _requestList(void)
Internal call to request list of mission items. May be called during a retry sequence.
void _writeMissionItemsWorker(void)
void _connectToMavlink(void)
AckType_t _expectedAck
static constexpr int _ackTimeoutMilliseconds
Definition PlanManager.h:59
void _startAckTimeout(AckType_t ack)
void loadFromVehicle(void)
void _sendError(ErrorCode_t errorCode, const QString &errorMsg)
void removeAllComplete(bool error)
void writeMissionItems(const QList< MissionItem * > &missionItems)
QList< int > _itemIndicesToWrite
List of mission items which still need to be written to vehicle.
void _handleMissionAck(const mavlink_message_t &message)
void _removeAllWorker(void)
@ TransactionRemoveAll
Definition PlanManager.h:97
void _clearMissionItems(void)
bool inProgress(void) const
void inProgressChanged(bool inProgress)
QList< MissionItem * > _writeMissionItems
Set of mission items currently being written to vehicle.
void progressPctChanged(double progressPercentPct)
void _clearAndDeleteMissionItems(void)
@ AckMissionItem
MISSION_ITEM expected.
Definition PlanManager.h:87
@ AckMissionRequest
MISSION_REQUEST is expected, or MISSION_ACK to end sequence.
Definition PlanManager.h:88
@ AckMissionCount
MISSION_COUNT message expected.
Definition PlanManager.h:86
@ AckMissionClearAll
MISSION_CLEAR_ALL sent, MISSION_ACK is expected.
Definition PlanManager.h:89
@ AckNone
State machine is idle.
Definition PlanManager.h:85
@ AckGuidedItem
MISSION_ACK expected in response to ArduPilot guided mode single item send.
Definition PlanManager.h:90
QString _planTypeString(void)
static constexpr int _retryTimeoutMilliseconds
Definition PlanManager.h:61
const QList< MissionItem * > & missionItems(void)
Definition PlanManager.h:22
void _requestNextMissionItem(void)
void _writeMissionCount(void)
This begins the write sequence with the vehicle. This may be called during a retry.
QString _ackTypeToString(AckType_t ackType)
void _handleMissionCount(const mavlink_message_t &message)
void _disconnectFromMavlink(void)
Vehicle * _vehicle
void error(int errorCode, const QString &errorMsg)
void _readTransactionComplete(void)