3#include <QtCore/QObject>
4#include <QtCore/QTimer>
70 void error (
int errorCode,
const QString& errorMsg);
81 void _ackTimeout(
void);
struct __mavlink_message mavlink_message_t
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....
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.
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void sendComplete(bool error)
void _handleMissionItem(const mavlink_message_t &message)
void resumeMissionReady(void)
int lastCurrentIndex(void) const
Last current mission item reported while in Mission flight mode.
void _clearAndDeleteWriteMissionItems(void)
QTimer * _ackTimeoutTimer
ErrorCode_t
Error codes returned in error signal.
@ 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.
static constexpr int kTestAckTimeoutMs
Ack timeout used in unit tests (much shorter for faster tests)
void newMissionItemsAvailable(bool removeAllRequested)
MAV_MISSION_TYPE _planType
QString _missionResultToString(MAV_MISSION_RESULT result)
QString _lastMissionReqestString(MAV_MISSION_RESULT result)
static constexpr int _maxRetryCount
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)
static constexpr int _ackTimeoutMilliseconds
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)
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.
@ 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.
QString _planTypeString(void)
static constexpr int _retryTimeoutMilliseconds
const QList< MissionItem * > & missionItems(void)
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)
void error(int errorCode, const QString &errorMsg)
void _readTransactionComplete(void)