mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
GCS_MAVLink: use new filesystem crc32 method
This commit is contained in:
parent
2c7e06dc5e
commit
423a218643
@ -444,26 +444,12 @@ void GCS_MAVLINK::ftp_worker(void) {
|
||||
|
||||
request.data[sizeof(request.data) - 1] = 0; // ensure the path is null terminated
|
||||
|
||||
// actually open the file
|
||||
int fd = AP::FS().open((char *)request.data, O_RDONLY);
|
||||
if (fd == -1) {
|
||||
uint32_t checksum = 0;
|
||||
if (!AP::FS().crc32((char *)request.data, checksum)) {
|
||||
ftp_error(reply, FTP_ERROR::FailErrno);
|
||||
break;
|
||||
}
|
||||
|
||||
uint32_t checksum = 0;
|
||||
ssize_t read_size;
|
||||
do {
|
||||
read_size = AP::FS().read(fd, reply.data, sizeof(reply.data));
|
||||
if (read_size == -1) {
|
||||
ftp_error(reply, FTP_ERROR::FailErrno);
|
||||
break;
|
||||
}
|
||||
checksum = crc_crc32(checksum, reply.data, MIN((size_t)read_size, sizeof(reply.data)));
|
||||
} while (read_size > 0);
|
||||
|
||||
AP::FS().close(fd);
|
||||
|
||||
// reset our scratch area so we don't leak data, and can leverage trimming
|
||||
memset(reply.data, 0, sizeof(reply.data));
|
||||
reply.size = sizeof(uint32_t);
|
||||
|
Loading…
Reference in New Issue
Block a user