diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 3ffb4672f07b5cfbed4c5af77b4691fd905d38bd..a91eb23ed6761515ebacb65de8183a392d29094a 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1875,6 +1875,14 @@ void Vehicle::_sendMavCommandAgain(void) } if (_mavCommandRetryCount > 1) { + if (queuedCommand.command == MAV_CMD_START_RX_PAIR) { + // Implementation of this command in all firmwares is incorrect. It does not send Ack so we can't retry. + return; + } + if (px4Firmware()) { + // PX4 stack is inconsistent with repect to sending back an Ack from a COMMAND_LONG, hence we can't support retry logic for it. + return; + } qDebug() << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount; }