Commit 0f3a711f authored by Don Gagne's avatar Don Gagne

parent d7643d24
...@@ -3214,26 +3214,11 @@ void Vehicle::_sendMavCommandAgain(void) ...@@ -3214,26 +3214,11 @@ void Vehicle::_sendMavCommandAgain(void)
} }
if (_mavCommandRetryCount > 1) { if (_mavCommandRetryCount > 1) {
// We always let AUTOPILOT_CAPABILITIES go through multiple times even if we don't get acks. This is because if (!px4Firmware() && queuedCommand.command == MAV_CMD_START_RX_PAIR) {
// we really need to get capabilities and version info back over a lossy link.
if (queuedCommand.command != MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
if (px4Firmware()) {
// Older PX4 firmwares are inconsistent with repect to sending back an Ack from a COMMAND_LONG, hence we can't support retry logic for it.
if (_firmwareMajorVersion != versionNotSetValue) {
// If no version set assume lastest master dev build, so acks are suppored
if (_firmwareMajorVersion <= 1 && _firmwareMinorVersion <= 5 && _firmwarePatchVersion <= 3) {
// Acks not supported in this version
return;
}
}
} else {
if (queuedCommand.command == MAV_CMD_START_RX_PAIR) {
// The implementation of this command comes from the IO layer and is shared across stacks. So for other firmwares // The implementation of this command comes from the IO layer and is shared across stacks. So for other firmwares
// we aren't really sure whether they are correct or not. // we aren't really sure whether they are correct or not.
return; return;
} }
}
}
qCDebug(VehicleLog) << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount; qCDebug(VehicleLog) << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount;
} }
...@@ -3319,7 +3304,7 @@ void Vehicle::_handleUnsupportedRequestProtocolVersion(void) ...@@ -3319,7 +3304,7 @@ void Vehicle::_handleUnsupportedRequestProtocolVersion(void)
void Vehicle::_protocolVersionTimeOut(void) void Vehicle::_protocolVersionTimeOut(void)
{ {
// The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC. // The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC.
// This means although the vehicle may support mavlink 1, the pipe does not. // This means although the vehicle may support mavlink 2, the pipe does not.
qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to 100 due to timeout on receiving PROTOCOL_VERSION message."); qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to 100 due to timeout on receiving PROTOCOL_VERSION message.");
_setMaxProtoVersion(100); _setMaxProtoVersion(100);
_mavlinkProtocolRequestComplete = true; _mavlinkProtocolRequestComplete = true;
......
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