mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: Strictly handle NACK/ACK
This is a change in bevaiour. The previous behaviour was to check for a NACK, and if it wasn't a NACK it was assumed to be an ACK. This is a bad assumption to let people get away with, because in the future if we ever add other options to the enum we are more likely to have to cope with bad implementation in the wild
This commit is contained in:
parent
4108e4b77f
commit
0c73da5e79
|
@ -274,10 +274,16 @@ void AP_Logger_MAVLink::remote_log_block_status_msg(const GCS_MAVLINK &link,
|
|||
if (!semaphore.take_nonblocking()) {
|
||||
return;
|
||||
}
|
||||
if(packet.status == MAV_REMOTE_LOG_DATA_BLOCK_NACK) {
|
||||
handle_retry(packet.seqno);
|
||||
} else {
|
||||
handle_ack(link, msg, packet.seqno);
|
||||
switch ((MAV_REMOTE_LOG_DATA_BLOCK_STATUSES)packet.status) {
|
||||
case MAV_REMOTE_LOG_DATA_BLOCK_NACK:
|
||||
handle_retry(packet.seqno);
|
||||
break;
|
||||
case MAV_REMOTE_LOG_DATA_BLOCK_ACK:
|
||||
handle_ack(link, msg, packet.seqno);
|
||||
break;
|
||||
// we apparently have to handle an END enum entry, just drop it so we catch future additions
|
||||
case MAV_REMOTE_LOG_DATA_BLOCK_STATUSES_ENUM_END:
|
||||
break;
|
||||
}
|
||||
semaphore.give();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue