QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkMissionItemHandler.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QMap>
4#include <QtCore/QObject>
5#include <QtCore/QTimer>
6
7#include "MAVLinkLib.h"
8
9class MockLink;
10
11class MockLinkMissionItemHandler : public QObject
12{
13 Q_OBJECT
14
15public:
18
19 // Prepares for destruction on correct thread
20 void shutdown();
21
26
28 FailNone, // No failures
29 FailReadRequestListNoResponse, // Don't send MISSION_COUNT in response to MISSION_REQUEST_LIST
30 FailReadRequestListFirstResponse, // Don't send MISSION_COUNT in response to first MISSION_REQUEST_LIST, allow subsequent to go through
31 FailReadRequest0NoResponse, // Don't send MISSION_ITEM in response to MISSION_REQUEST item 0
32 FailReadRequest1NoResponse, // Don't send MISSION_ITEM in response to MISSION_REQUEST item 1
33 FailReadRequest1FirstResponse, // Don't send MISSION_ITEM in response to MISSION_REQUEST item 1 on first try, allow subsequent request to go through
34 FailReadRequest0IncorrectSequence, // Respond to MISSION_REQUEST 0 with incorrect sequence number in MISSION_ITEM
35 FailReadRequest1IncorrectSequence, // Respond to MISSION_REQUEST 1 with incorrect sequence number in MISSION_ITEM
36 FailReadRequest0ErrorAck, // Respond to MISSION_REQUEST 0 with MISSION_ACK error
37 FailReadRequest1ErrorAck, // Respond to MISSION_REQUEST 1 bogus MISSION_ACK error
38 FailWriteMissionCountNoResponse, // Don't respond to MISSION_COUNT with MISSION_REQUEST 0
39 FailWriteMissionCountFirstResponse, // Don't respond to first MISSION_COUNT with MISSION_REQUEST 0, respond to subsequent MISSION_COUNT requests
40 FailWriteRequest1NoResponse, // Don't respond to MISSION_ITEM 0 with MISSION_REQUEST 1
41 FailWriteRequest0IncorrectSequence, // Item 0 MISSION_REQUEST sent has wrong sequence number
42 FailWriteRequest1IncorrectSequence, // Item 1 MISSION_REQUEST sent has wrong sequence number
43 FailWriteRequest0ErrorAck, // Instead of sending MISSION_REQUEST 0, send MISSION_ACK error
44 FailWriteRequest1ErrorAck, // Instead of sending MISSION_REQUEST 1, send MISSION_ACK error
45 FailWriteFinalAckNoResponse, // Don't send the final MISSION_ACK
46 FailWriteFinalAckErrorAck, // Send an error as the final MISSION_ACK
47 FailWriteFinalAckMissingRequests, // Send the MISSION_ACK before all items have been requested
48 };
49
53 void setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult);
54
56 void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType);
57
60
63
65 void reset() { _missionItems.clear(); _requestListCounts.clear(); }
66
67 void setSendHomePositionOnEmptyList(bool sendHomePositionOnEmptyList) { _sendHomePositionOnEmptyList = sendHomePositionOnEmptyList; }
68
69 int requestListCount(MAV_MISSION_TYPE type) const { return _requestListCounts.value(type, 0); }
70 void clearRequestListCounts() { _requestListCounts.clear(); }
71
72private slots:
73 void _missionItemResponseTimeout();
74
75private:
76 void _handleMissionRequestList(const mavlink_message_t &msg);
77 void _handleMissionRequest(const mavlink_message_t &msg);
78 void _handleMissionItem(const mavlink_message_t &msg);
79 void _handleMissionCount(const mavlink_message_t &msg);
80 void _handleMissionClearAll(const mavlink_message_t &msg);
81 void _requestNextMissionItem(int sequenceNumber);
82 void _sendAck(MAV_MISSION_RESULT ackType) const;
83 void _startMissionItemResponseTimer();
84
85 MockLink *_mockLink = nullptr;
86
87 int _writeSequenceCount = 0;
88 int _writeSequenceIndex = 0;
89
90 typedef QMap<uint16_t, mavlink_mission_item_int_t> MissionItemList_t;
91
92 MAV_MISSION_TYPE _requestType = MAV_MISSION_TYPE_MISSION;
93 MissionItemList_t _missionItems;
94 MissionItemList_t _fenceItems;
95 MissionItemList_t _rallyItems;
96
97 QTimer _missionItemResponseTimer;
98 FailureMode_t _failureMode = FailNone;
99 MAV_MISSION_RESULT _failureAckResult;
100 bool _sendHomePositionOnEmptyList = false;
101 bool _failReadRequestListFirstResponse = true;
102 bool _failReadRequest1FirstResponse = true;
103 bool _failWriteMissionCountFirstResponse = true;
104 QMap<MAV_MISSION_TYPE, int> _requestListCounts;
105};
struct __mavlink_message mavlink_message_t
int requestListCount(MAV_MISSION_TYPE type) const
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType)
Called to send a MISSION_ACK message while the MissionManager is in idle state.
void reset()
Reset the state of the MissionItemHandler to no items, no transactions in progress.
bool handleMavlinkMessage(const mavlink_message_t &msg)
void setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
void setSendHomePositionOnEmptyList(bool sendHomePositionOnEmptyList)
void sendUnexpectedMissionRequest()
Called to send a MISSION_REQUEST message while the MissionManager is in idle state.
void sendUnexpectedMissionItem()
Called to send a MISSION_ITEM message while the MissionManager is in idle state.