Skip to content
Snippets Groups Projects
Commit 438cf74c authored by DonLakeFlyer's avatar DonLakeFlyer
Browse files

Carryover ArduPilot changes from stable

parent e3833aa5
No related branches found
No related tags found
No related merge requests found
...@@ -589,6 +589,14 @@ void PlanManager::_handleMissionAck(const mavlink_message_t& message) ...@@ -589,6 +589,14 @@ void PlanManager::_handleMissionAck(const mavlink_message_t& message)
return; return;
} }
if (_vehicle->apmFirmware() && missionAck.type == MAV_MISSION_INVALID_SEQUENCE) {
// ArduPilot sends these Acks which can happen just due to noisy links causing duplicated requests being responded to.
// As far as I'm concerned this is incorrect protocol implementation but we need to deal with it anyway. So we just
// ignore it and if things really go haywire the timeouts will fire to fail the overall transaction.
qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck ArduPilot sending possibly bogus MAV_MISSION_INVALID_SEQUENCE").arg(_planTypeString()) << _planType;
return;
}
// Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what // Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what
// type of a protocol sequence we are in. // type of a protocol sequence we are in.
AckType_t savedExpectedAck = _expectedAck; AckType_t savedExpectedAck = _expectedAck;
......
...@@ -71,7 +71,7 @@ public: ...@@ -71,7 +71,7 @@ public:
// These values are public so the unit test can set appropriate signal wait times // These values are public so the unit test can set appropriate signal wait times
// When passively waiting for a mission process, use a longer timeout. // When passively waiting for a mission process, use a longer timeout.
static const int _ackTimeoutMilliseconds = 1000; static const int _ackTimeoutMilliseconds = 1500;
// When actively retrying to request mission items, use a shorter timeout instead. // When actively retrying to request mission items, use a shorter timeout instead.
static const int _retryTimeoutMilliseconds = 250; static const int _retryTimeoutMilliseconds = 250;
static const int _maxRetryCount = 5; static const int _maxRetryCount = 5;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment