mavlink: add more error messages

This commit is contained in:
Julian Oes 2021-06-22 15:47:35 +02:00 committed by Daniel Agar
parent 74b2fe326d
commit 59b56dd06f

View File

@ -165,7 +165,7 @@ MavlinkFTP::_process_request(
// basic sanity checks; must validate length before use
if (payload->size > kMaxDataLength) {
errorCode = kErrInvalidDataSize;
PX4_DEBUG("invalid data size");
PX4_WARN("invalid data size");
goto out;
}
@ -517,7 +517,7 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
// fail only if requested open for read
if (oflag & O_RDONLY) {
_our_errno = errno;
PX4_DEBUG("stat failed read: %s", strerror(_our_errno));
PX4_ERR("stat failed read: %s", strerror(_our_errno));
return kErrFailErrno;
} else {
@ -533,7 +533,7 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
if (fd < 0) {
_our_errno = errno;
PX4_DEBUG("open failed: %s", strerror(_our_errno));
PX4_ERR("open failed: %s", strerror(_our_errno));
return kErrFailErrno;
}
@ -1074,7 +1074,7 @@ void MavlinkFTP::send()
if (error_code == kErrNone) {
if (lseek(_session_info.fd, payload->offset, SEEK_SET) < 0) {
error_code = kErrFailErrno;
PX4_DEBUG("stream download: seek fail");
PX4_WARN("stream download: seek fail");
}
}
@ -1084,7 +1084,7 @@ void MavlinkFTP::send()
if (bytes_read < 0) {
// Negative return indicates error other than eof
error_code = kErrFailErrno;
PX4_DEBUG("stream download: read fail");
PX4_WARN("stream download: read fail");
} else {
payload->size = bytes_read;