mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
mavlink_ftp: fix tests after implementation fix
In commit 462b572172 the reading operation
on the PX4 side was changed to only read as many bytes as requested
rather than however many fit in the payload data.
This caused the unit tests to fail which this commit here aims to fix.
What is confusing about MAVLink FTP is that there is a size field which
generally signals how many bytes of the payload data are used/set.
However, in the case of a read requst, the size field is used to
indicate how many bytes should be read. The payload data is empty in
that case though.
This case was, from how I understand it, not implemented/tested in the
unit tests and now failed. In order to implement it I had to change a
few things:
- Change _setup_ftp_msg and _send_receive_msg so that the params contain
a data length rather than the size field. The size field itself needs
to be set outside of these methods using payload->size.
- Since we test files smaller, equal, and bigger than one payload data
length, I implemented that we send multiple read requests until we
have the whole file and not just the first part.
- Additionally, I saw a lot of uninitialized warnings in valgrind, and
got rid of them by adding a few zero initializations.
This commit is contained in:
@@ -165,7 +165,7 @@ MavlinkFTP::_process_request(
|
||||
// basic sanity checks; must validate length before use
|
||||
if (payload->size > kMaxDataLength) {
|
||||
errorCode = kErrInvalidDataSize;
|
||||
PX4_WARN("invalid data size");
|
||||
PX4_WARN("invalid data size: %d", payload->size);
|
||||
goto out;
|
||||
}
|
||||
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -98,12 +98,13 @@ private:
|
||||
bool _removefile_test(void);
|
||||
|
||||
void _receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req);
|
||||
void _setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data,
|
||||
bool _setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header,
|
||||
const uint8_t *data, const uint8_t data_len,
|
||||
mavlink_message_t *msg);
|
||||
bool _decode_message(const mavlink_file_transfer_protocol_t *ftp_msg, const MavlinkFTP::PayloadHeader **payload);
|
||||
bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header,
|
||||
uint8_t size,
|
||||
const uint8_t *data,
|
||||
const size_t data_len,
|
||||
const MavlinkFTP::PayloadHeader **payload_reply);
|
||||
void _cleanup_microsd(void);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user