3#include <QtCore/QObject>
4#include <QtCore/QTimer>
5#include <QtCore/QLoggingCategory>
24 bool inProgress(
void)
const;
25 const QList<MissionItem*>&
missionItems(
void) {
return _missionItems; }
35 void loadFromVehicle(
void);
41 void writeMissionItems(
const QList<MissionItem*>& missionItems);
62 static constexpr int _ackTimeoutMilliseconds = 1500;
64 static constexpr int _retryTimeoutMilliseconds = 250;
65 static constexpr int _maxRetryCount = 5;
68 static constexpr int kTestAckTimeoutMs = 50;
73 void error (
int errorCode,
const QString& errorMsg);
84 void _ackTimeout(
void);
103 void _startAckTimeout(AckType_t ack);
104 bool _checkForExpectedAck(AckType_t receivedAck);
105 void _readTransactionComplete(
void);
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);
131 QTimer* _ackTimeoutTimer =
nullptr;
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
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.
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.
@ AckTimeoutError
Timed out waiting for response from vehicle.
@ ItemMismatchError
Vehicle returned item with seq # different than requested.
@ MaxRetryExceeded
Retry failed.
@ MissionTypeMismatch
MAV_MISSION_TYPE does not match _planType.
@ ProtocolError
Incorrect protocol sequence from vehicle.
@ MissingRequestsError
Vehicle did not request all items during write sequence.
@ RequestRangeError
Vehicle requested item out of range.
@ VehicleAckError
Vehicle returned error in ack.
int _missionItemCountToRead
Count of all mission items to read.
void newMissionItemsAvailable(bool removeAllRequested)
MAV_MISSION_TYPE _planType
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.
@ AckMissionRequest
MISSION_REQUEST is expected, or MISSION_ACK to end sequence.
@ AckMissionCount
MISSION_COUNT message expected.
@ AckMissionClearAll
MISSION_CLEAR_ALL sent, MISSION_ACK is expected.
@ AckNone
State machine is idle.
@ AckGuidedItem
MISSION_ACK expected in response to ArduPilot guided mode single item send.
const QList< MissionItem * > & missionItems(void)
void error(int errorCode, const QString &errorMsg)