mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: fixed a ftp duplicate reply
this fixes a bug in burst replies where the duplicate reply may have the wrong offset. This causes the "paramftp bad type" error
This commit is contained in:
parent
64360f263c
commit
fc28cd4fa2
|
@ -168,6 +168,8 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||
reply.session = -1; // flag the reply as invalid for any reuse
|
||||
|
||||
while (true) {
|
||||
bool skip_push_reply = false;
|
||||
|
||||
while (!ftp.requests->pop(request)) {
|
||||
// nothing to handle, delay ourselves a bit then check again. Ideally we'd use conditional waits here
|
||||
hal.scheduler->delay(2);
|
||||
|
@ -527,6 +529,11 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||
reply.seq_number++;
|
||||
}
|
||||
|
||||
if (reply.opcode != FTP_OP::Nack) {
|
||||
// prevent a duplicate packet send for
|
||||
// normal replies of burst reads
|
||||
skip_push_reply = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case FTP_OP::TruncateFile:
|
||||
|
@ -539,7 +546,10 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||
}
|
||||
}
|
||||
|
||||
ftp_push_replies(reply);
|
||||
if (!skip_push_reply) {
|
||||
ftp_push_replies(reply);
|
||||
}
|
||||
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue