17 (void) connect(&_missionItemResponseTimer, &QTimer::timeout,
this, &MockLinkMissionItemHandler::_missionItemResponseTimeout);
25void MockLinkMissionItemHandler::_startMissionItemResponseTimer()
27 _missionItemResponseTimer.start(500);
33 case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
34 _handleMissionRequestList(msg);
36 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
37 _handleMissionRequest(msg);
39 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
40 _handleMissionItem(msg);
42 case MAVLINK_MSG_ID_MISSION_COUNT:
43 _handleMissionCount(msg);
45 case MAVLINK_MSG_ID_MISSION_ACK:
48 case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
51 case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
52 _handleMissionClearAll(msg);
61void MockLinkMissionItemHandler::_handleMissionClearAll(
const mavlink_message_t &msg)
63 mavlink_mission_clear_all_t clearAll{};
64 mavlink_msg_mission_clear_all_decode(&msg, &clearAll);
66 Q_ASSERT(clearAll.target_system == _mockLink->
vehicleId());
68 _requestType =
static_cast<MAV_MISSION_TYPE
>(clearAll.mission_type);
69 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionClearAll" << _requestType;
71 switch (_requestType) {
72 case MAV_MISSION_TYPE_MISSION:
73 _missionItems.clear();
75 case MAV_MISSION_TYPE_FENCE:
78 case MAV_MISSION_TYPE_RALLY:
81 case MAV_MISSION_TYPE_ALL:
82 _missionItems.clear();
90 _sendAck(MAV_MISSION_ACCEPTED);
93void MockLinkMissionItemHandler::_handleMissionRequestList(
const mavlink_message_t &msg)
95 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequestList read sequence";
97 _failReadRequest1FirstResponse =
true;
99 mavlink_mission_request_list_t request{};
100 mavlink_msg_mission_request_list_decode(&msg, &request);
103 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequestList not responding due to failure mode FailReadRequestListNoResponse";
108 _failReadRequestListFirstResponse =
false;
109 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequestList not responding due to failure mode FailReadRequestListFirstResponse";
113 _failReadRequestListFirstResponse =
true;
115 Q_ASSERT(request.target_system == _mockLink->
vehicleId());
116 _requestListCounts[
static_cast<MAV_MISSION_TYPE
>(request.mission_type)]++;
118 _requestType =
static_cast<MAV_MISSION_TYPE
>(request.mission_type);
121 switch (_requestType) {
122 case MAV_MISSION_TYPE_MISSION:
123 itemCount = _missionItems.count();
124 if (itemCount == 0 && _sendHomePositionOnEmptyList) {
128 case MAV_MISSION_TYPE_FENCE:
129 itemCount = _fenceItems.count();
131 case MAV_MISSION_TYPE_RALLY:
132 itemCount = _rallyItems.count();
139 (void) mavlink_msg_mission_count_pack_chan(
141 MAV_COMP_ID_AUTOPILOT1,
154void MockLinkMissionItemHandler::_handleMissionRequest(
const mavlink_message_t &msg)
156 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest read sequence";
158 mavlink_mission_request_int_t request{};
159 mavlink_msg_mission_request_int_decode(&msg, &request);
161 Q_ASSERT(request.target_system == _mockLink->
vehicleId());
164 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest not responding due to failure mode FailReadRequest0NoResponse";
169 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest not responding due to failure mode FailReadRequest1NoResponse";
174 _failReadRequest1FirstResponse =
false;
175 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest not responding due to failure mode FailReadRequest1FirstResponse";
184 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest sending bad sequence number";
190 _sendAck(_failureAckResult);
194 mavlink_mission_item_int_t missionItemInt{};
196 switch (request.mission_type) {
197 case MAV_MISSION_TYPE_MISSION:
198 if (_missionItems.isEmpty() && _sendHomePositionOnEmptyList) {
199 (void) memset(&missionItemInt, 0,
sizeof(missionItemInt));
200 missionItemInt.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
201 missionItemInt.command = MAV_CMD_NAV_WAYPOINT;
202 missionItemInt.autocontinue =
true;
204 missionItemInt = _missionItems[request.seq];
207 case MAV_MISSION_TYPE_FENCE:
208 missionItemInt = _fenceItems[request.seq];
210 case MAV_MISSION_TYPE_RALLY:
211 missionItemInt = _rallyItems[request.seq];
218 (void) mavlink_msg_mission_item_int_pack_chan(
220 MAV_COMP_ID_AUTOPILOT1,
226 missionItemInt.frame,
227 missionItemInt.command,
228 missionItemInt.current,
229 missionItemInt.autocontinue,
230 missionItemInt.param1, missionItemInt.param2, missionItemInt.param3, missionItemInt.param4,
231 missionItemInt.x, missionItemInt.y, missionItemInt.z,
238void MockLinkMissionItemHandler::_handleMissionCount(
const mavlink_message_t &msg)
240 mavlink_mission_count_t missionCount{};
241 mavlink_msg_mission_count_decode(&msg, &missionCount);
242 Q_ASSERT(missionCount.target_system == _mockLink->
vehicleId());
244 _requestType = (MAV_MISSION_TYPE)missionCount.mission_type;
245 _writeSequenceCount = missionCount.count;
246 Q_ASSERT(_writeSequenceCount >= 0);
248 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
250 switch (missionCount.mission_type) {
251 case MAV_MISSION_TYPE_MISSION:
252 _missionItems.clear();
254 case MAV_MISSION_TYPE_FENCE:
257 case MAV_MISSION_TYPE_RALLY:
262 if (_writeSequenceCount == 0) {
263 _sendAck(MAV_MISSION_ACCEPTED);
268 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
273 _failWriteMissionCountFirstResponse =
false;
274 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
278 _failWriteMissionCountFirstResponse =
true;
279 _writeSequenceIndex = 0;
280 _requestNextMissionItem(_writeSequenceIndex);
283void MockLinkMissionItemHandler::_requestNextMissionItem(
int sequenceNumber)
285 qCDebug(MockLinkMissionItemHandlerLog) <<
"write sequence sequenceNumber:" << sequenceNumber <<
"_failureMode:" << _failureMode;
288 qCDebug(MockLinkMissionItemHandlerLog) <<
"_requestNextMissionItem not responding due to failure mode FailWriteRequest1NoResponse";
292 if (sequenceNumber >= _writeSequenceCount) {
293 qCWarning(MockLinkMissionItemHandlerLog) <<
"_requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount" << sequenceNumber << _writeSequenceCount;
304 qCDebug(MockLinkMissionItemHandlerLog) <<
"_requestNextMissionItem sending ack error due to failure mode";
305 _sendAck(_failureAckResult);
310 (void) mavlink_msg_mission_request_int_pack_chan(
312 MAV_COMP_ID_AUTOPILOT1,
323 _startMissionItemResponseTimer();
326void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
const
328 qCDebug(MockLinkMissionItemHandlerLog) <<
"_sendAck write sequence complete ackType:" << ackType;
331 (void) mavlink_msg_mission_ack_pack_chan(
333 MAV_COMP_ID_AUTOPILOT1,
348 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionItem write sequence";
350 _missionItemResponseTimer.stop();
352 mavlink_mission_item_int_t missionItemInt{};
353 mavlink_msg_mission_item_int_decode(&msg, &missionItemInt);
355 const MAV_MISSION_TYPE missionType =
static_cast<MAV_MISSION_TYPE
>(missionItemInt.mission_type);
356 const uint16_t seq = missionItemInt.seq;
358 switch (missionType) {
359 case MAV_MISSION_TYPE_MISSION:
360 _missionItems[seq] = missionItemInt;
362 case MAV_MISSION_TYPE_FENCE:
363 _fenceItems[seq] = missionItemInt;
365 case MAV_MISSION_TYPE_RALLY:
366 _rallyItems[seq] = missionItemInt;
368 case MAV_MISSION_TYPE_ENUM_END:
369 case MAV_MISSION_TYPE_ALL:
370 qCWarning(MockLinkMissionItemHandlerLog) <<
"Internal error";
374 _writeSequenceIndex++;
375 if (_writeSequenceIndex < _writeSequenceCount) {
378 _sendAck(MAV_MISSION_ACCEPTED);
380 _requestNextMissionItem(_writeSequenceIndex);
387 MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED;
390 ack = MAV_MISSION_ERROR;
397void MockLinkMissionItemHandler::_missionItemResponseTimeout()
399 qCWarning(MockLinkMissionItemHandlerLog) <<
"Timeout waiting for next MISSION_ITEM_INT";
422 _failureMode = failureMode;
423 _failureAckResult = failureAckResult;
428 _missionItemResponseTimer.stop();
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
static int getComponentId()
static MAVLinkProtocol * instance()
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType)
Called to send a MISSION_ACK message while the MissionManager is in idle state.
bool handleMavlinkMessage(const mavlink_message_t &msg)
void setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
void sendUnexpectedMissionRequest()
Called to send a MISSION_REQUEST message while the MissionManager is in idle state.
@ FailWriteFinalAckMissingRequests
@ FailWriteFinalAckNoResponse
@ FailWriteRequest1IncorrectSequence
@ FailWriteMissionCountFirstResponse
@ FailWriteRequest1ErrorAck
@ FailWriteRequest0ErrorAck
@ FailReadRequest1IncorrectSequence
@ FailReadRequest0IncorrectSequence
@ FailWriteMissionCountNoResponse
@ FailWriteRequest1NoResponse
@ FailReadRequest1ErrorAck
@ FailWriteFinalAckErrorAck
@ FailReadRequest0NoResponse
@ FailReadRequest1NoResponse
@ FailReadRequestListFirstResponse
@ FailReadRequest0ErrorAck
@ FailWriteRequest0IncorrectSequence
@ FailReadRequestListNoResponse
@ FailReadRequest1FirstResponse
void sendUnexpectedMissionItem()
Called to send a MISSION_ITEM message while the MissionManager is in idle state.
~MockLinkMissionItemHandler()
void respondWithMavlinkMessage(const mavlink_message_t &msg)
Sends the specified mavlink message to QGC.