aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_ftp.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-08 09:58:08 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-08 09:58:08 +0200
commit9f1661f1f8808b7c83f73284cee9a1e9279165d3 (patch)
treea3cd505a7f47324706acdcfb00048f651dd9f209 /src/modules/mavlink/mavlink_ftp.cpp
parent0d0c4c36265b044ba978cfe4dbe369e93aa25d44 (diff)
downloadpx4-firmware-9f1661f1f8808b7c83f73284cee9a1e9279165d3.tar.gz
px4-firmware-9f1661f1f8808b7c83f73284cee9a1e9279165d3.tar.bz2
px4-firmware-9f1661f1f8808b7c83f73284cee9a1e9279165d3.zip
Silence FTP transactions, be vocal about errors
Diffstat (limited to 'src/modules/mavlink/mavlink_ftp.cpp')
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp19
1 files changed, 10 insertions, 9 deletions
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 57ae6076c..675a6870e 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -117,10 +117,10 @@ MavlinkFTP::_worker(Request *req)
if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
errorCode = kErrNoRequest;
goto out;
- printf("ftp: bad crc\n");
+ warnx("ftp: bad crc");
}
- printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
+ //printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
switch (hdr->opcode) {
case kCmdNone:
@@ -167,9 +167,9 @@ out:
// handle success vs. error
if (errorCode == kErrNone) {
hdr->opcode = kRspAck;
- printf("FTP: ack\n");
+ //warnx("FTP: ack\n");
} else {
- printf("FTP: nak %u\n", errorCode);
+ warnx("FTP: nak %u", errorCode);
hdr->opcode = kRspNak;
hdr->size = 1;
hdr->data[0] = errorCode;
@@ -206,11 +206,11 @@ MavlinkFTP::_workList(Request *req)
DIR *dp = opendir(dirPath);
if (dp == nullptr) {
- printf("FTP: can't open path '%s'\n", dirPath);
+ warnx("FTP: can't open path '%s'", dirPath);
return kErrNotDir;
}
- printf("FTP: list %s offset %d\n", dirPath, hdr->offset);
+ //warnx("FTP: list %s offset %d", dirPath, hdr->offset);
ErrorCode errorCode = kErrNone;
struct dirent entry, *result = nullptr;
@@ -222,7 +222,7 @@ MavlinkFTP::_workList(Request *req)
for (;;) {
// read the directory entry
if (readdir_r(dp, &entry, &result)) {
- printf("FTP: list %s readdir_r failure\n", dirPath);
+ warnx("FTP: list %s readdir_r failure\n", dirPath);
errorCode = kErrIO;
break;
}
@@ -304,19 +304,20 @@ MavlinkFTP::_workRead(Request *req)
}
// Seek to the specified position
- printf("Seek %d\n", hdr->offset);
+ //warnx("seek %d", hdr->offset);
if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
// Unable to see to the specified location
+ warnx("seek fail");
return kErrEOF;
}
int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
if (bytes_read < 0) {
// Negative return indicates error other than eof
+ warnx("read fail %d", bytes_read);
return kErrIO;
}
- printf("Read success %d\n", bytes_read);
hdr->size = bytes_read;
return kErrNone;