Commit 8ff3985b authored by Don Gagne's avatar Don Gagne

parent ef759624
......@@ -698,12 +698,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
}
}
if (!foundRequest) {
if (++_capabilitiesRetryCount > 5) {
_capabilitiesRetryCount++;
if (_capabilitiesRetryCount == 1) {
_capabilitiesRetryElapsed.start();
} else if (_capabilitiesRetryElapsed.elapsed() > 10000){
qCDebug(VehicleLog) << "Giving up on getting AUTOPILOT_VERSION after 10 seconds";
qgcApp()->showMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION"));
_handleUnsupportedRequestAutopilotCapabilities();
} else {
// Vehicle never sent us AUTOPILOT_VERSION response. Try again.
qCDebug(VehicleLog) << "Sending MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES again due to no response with AUTOPILOT_VERSION - _capabilitiesRetryCount" << _capabilitiesRetryCount;
qCDebug(VehicleLog) << QStringLiteral("Sending MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES again due to no response with AUTOPILOT_VERSION - _capabilitiesRetryCount(%1) elapsed(%2)").arg(_capabilitiesRetryCount).arg(_capabilitiesRetryElapsed.elapsed());
sendMavCommand(MAV_COMP_ID_ALL,
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
true, // Show error on failure
......
......@@ -12,6 +12,7 @@
#include <QObject>
#include <QVariantList>
#include <QGeoCoordinate>
#include <QTime>
#include "FactGroup.h"
#include "LinkInterface.h"
......@@ -1431,6 +1432,7 @@ private:
QTimer _mavCommandAckTimer;
int _mavCommandRetryCount;
int _capabilitiesRetryCount = 0;
QTime _capabilitiesRetryElapsed;
static const int _mavCommandMaxRetryCount = 3;
static const int _mavCommandAckTimeoutMSecs = 3000;
static const int _mavCommandAckTimeoutMSecsHighLatency = 120000;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment