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;
100 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequestList not responding due to failure mode FailReadRequestListNoResponse";
105 _failReadRequestListFirstResponse =
false;
106 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequestList not responding due to failure mode FailReadRequestListFirstResponse";
110 _failReadRequestListFirstResponse =
true;
112 mavlink_mission_request_list_t request{};
113 mavlink_msg_mission_request_list_decode(&msg, &request);
115 Q_ASSERT(request.target_system == _mockLink->
vehicleId());
117 _requestType =
static_cast<MAV_MISSION_TYPE
>(request.mission_type);
120 switch (_requestType) {
121 case MAV_MISSION_TYPE_MISSION:
122 itemCount = _missionItems.count();
123 if (itemCount == 0 && _sendHomePositionOnEmptyList) {
127 case MAV_MISSION_TYPE_FENCE:
128 itemCount = _fenceItems.count();
130 case MAV_MISSION_TYPE_RALLY:
131 itemCount = _rallyItems.count();
138 (void) mavlink_msg_mission_count_pack_chan(
140 MAV_COMP_ID_AUTOPILOT1,
153void MockLinkMissionItemHandler::_handleMissionRequest(
const mavlink_message_t &msg)
155 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest read sequence";
157 mavlink_mission_request_int_t request{};
158 mavlink_msg_mission_request_int_decode(&msg, &request);
160 Q_ASSERT(request.target_system == _mockLink->
vehicleId());
163 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest not responding due to failure mode FailReadRequest0NoResponse";
168 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest not responding due to failure mode FailReadRequest1NoResponse";
173 _failReadRequest1FirstResponse =
false;
174 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest not responding due to failure mode FailReadRequest1FirstResponse";
183 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionRequest sending bad sequence number";
189 _sendAck(_failureAckResult);
193 mavlink_mission_item_int_t missionItemInt{};
195 switch (request.mission_type) {
196 case MAV_MISSION_TYPE_MISSION:
197 if (_missionItems.isEmpty() && _sendHomePositionOnEmptyList) {
198 (void) memset(&missionItemInt, 0,
sizeof(missionItemInt));
199 missionItemInt.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
200 missionItemInt.command = MAV_CMD_NAV_WAYPOINT;
201 missionItemInt.autocontinue =
true;
203 missionItemInt = _missionItems[request.seq];
206 case MAV_MISSION_TYPE_FENCE:
207 missionItemInt = _fenceItems[request.seq];
209 case MAV_MISSION_TYPE_RALLY:
210 missionItemInt = _rallyItems[request.seq];
217 (void) mavlink_msg_mission_item_int_pack_chan(
219 MAV_COMP_ID_AUTOPILOT1,
225 missionItemInt.frame,
226 missionItemInt.command,
227 missionItemInt.current,
228 missionItemInt.autocontinue,
229 missionItemInt.param1, missionItemInt.param2, missionItemInt.param3, missionItemInt.param4,
230 missionItemInt.x, missionItemInt.y, missionItemInt.z,
237void MockLinkMissionItemHandler::_handleMissionCount(
const mavlink_message_t &msg)
239 mavlink_mission_count_t missionCount{};
240 mavlink_msg_mission_count_decode(&msg, &missionCount);
241 Q_ASSERT(missionCount.target_system == _mockLink->
vehicleId());
243 _requestType = (MAV_MISSION_TYPE)missionCount.mission_type;
244 _writeSequenceCount = missionCount.count;
245 Q_ASSERT(_writeSequenceCount >= 0);
247 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
249 switch (missionCount.mission_type) {
250 case MAV_MISSION_TYPE_MISSION:
251 _missionItems.clear();
253 case MAV_MISSION_TYPE_FENCE:
256 case MAV_MISSION_TYPE_RALLY:
261 if (_writeSequenceCount == 0) {
262 _sendAck(MAV_MISSION_ACCEPTED);
267 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
272 _failWriteMissionCountFirstResponse =
false;
273 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
277 _failWriteMissionCountFirstResponse =
true;
278 _writeSequenceIndex = 0;
279 _requestNextMissionItem(_writeSequenceIndex);
282void MockLinkMissionItemHandler::_requestNextMissionItem(
int sequenceNumber)
284 qCDebug(MockLinkMissionItemHandlerLog) <<
"write sequence sequenceNumber:" << sequenceNumber <<
"_failureMode:" << _failureMode;
287 qCDebug(MockLinkMissionItemHandlerLog) <<
"_requestNextMissionItem not responding due to failure mode FailWriteRequest1NoResponse";
291 if (sequenceNumber >= _writeSequenceCount) {
292 qCWarning(MockLinkMissionItemHandlerLog) <<
"_requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount" << sequenceNumber << _writeSequenceCount;
303 qCDebug(MockLinkMissionItemHandlerLog) <<
"_requestNextMissionItem sending ack error due to failure mode";
304 _sendAck(_failureAckResult);
309 (void) mavlink_msg_mission_request_int_pack_chan(
311 MAV_COMP_ID_AUTOPILOT1,
322 _startMissionItemResponseTimer();
325void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
const
327 qCDebug(MockLinkMissionItemHandlerLog) <<
"_sendAck write sequence complete ackType:" << ackType;
330 (void) mavlink_msg_mission_ack_pack_chan(
332 MAV_COMP_ID_AUTOPILOT1,
347 qCDebug(MockLinkMissionItemHandlerLog) <<
"_handleMissionItem write sequence";
349 _missionItemResponseTimer.stop();
351 mavlink_mission_item_int_t missionItemInt{};
352 mavlink_msg_mission_item_int_decode(&msg, &missionItemInt);
354 const MAV_MISSION_TYPE missionType =
static_cast<MAV_MISSION_TYPE
>(missionItemInt.mission_type);
355 const uint16_t seq = missionItemInt.seq;
357 switch (missionType) {
358 case MAV_MISSION_TYPE_MISSION:
359 _missionItems[seq] = missionItemInt;
361 case MAV_MISSION_TYPE_FENCE:
362 _fenceItems[seq] = missionItemInt;
364 case MAV_MISSION_TYPE_RALLY:
365 _rallyItems[seq] = missionItemInt;
367 case MAV_MISSION_TYPE_ENUM_END:
368 case MAV_MISSION_TYPE_ALL:
369 qCWarning(MockLinkMissionItemHandlerLog) <<
"Internal error";
373 _writeSequenceIndex++;
374 if (_writeSequenceIndex < _writeSequenceCount) {
377 _sendAck(MAV_MISSION_ACCEPTED);
379 _requestNextMissionItem(_writeSequenceIndex);
386 MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED;
389 ack = MAV_MISSION_ERROR;
396void MockLinkMissionItemHandler::_missionItemResponseTimeout()
398 qCWarning(MockLinkMissionItemHandlerLog) <<
"Timeout waiting for next MISSION_ITEM_INT";
421 _failureMode = failureMode;
422 _failureAckResult = failureAckResult;
427 _missionItemResponseTimer.stop();
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
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.