qCDebug(VehicleLog)<<"Giving up on getting AUTOPILOT_VERSION after 10 seconds";
qgcApp()->showAppMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION after waiting/retrying for 10 seconds"));
_handleUnsupportedRequestAutopilotCapabilities();
}else{
// Vehicle never sent us AUTOPILOT_VERSION response. Try again.
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
1);// Request firmware version
}
}
}
}
}
...
@@ -802,12 +777,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
...
@@ -802,12 +777,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
qCDebug(VehicleLog)<<QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result);