mavlink: add logging of mavlink messages back

The logging into a text file was commented out in the recent changes but
is added back in with this commit.
This commit is contained in:
Julian Oes 2016-03-21 12:59:13 +01:00
parent 198b8a299e
commit aecdd4e32f

View File

@ -374,6 +374,7 @@ private:
unsigned write_err_count = 0;
static const unsigned write_err_threshold = 5;
FILE *fp = nullptr;
protected:
explicit MavlinkStreamStatustext(Mavlink *mavlink) : MavlinkStream(mavlink),
@ -392,55 +393,52 @@ protected:
strncpy(msg.text, (const char*)mavlink_log.text, sizeof(msg.text));
_mavlink->send_message(MAVLINK_MSG_ID_STATUSTEXT, &msg);
}
// TODO: add this again
#if 0
/* write log messages in first instance to disk */
if (_mavlink->get_instance_id() == 0) {
if (fp) {
if (EOF == fputs(msg.text, fp)) {
write_err_count++;
} else {
write_err_count = 0;
}
/* write log messages in first instance to disk */
if (_mavlink->get_instance_id() == 0) {
if (fp) {
if (EOF == fputs(msg.text, fp)) {
write_err_count++;
} else {
write_err_count = 0;
}
if (write_err_count >= write_err_threshold) {
(void)fclose(fp);
fp = nullptr;
} else {
(void)fputs("\n", fp);
(void)fsync(fileno(fp));
}
if (write_err_count >= write_err_threshold) {
(void)fclose(fp);
fp = nullptr;
} else {
(void)fputs("\n", fp);
(void)fsync(fileno(fp));
}
} else if (write_err_count < write_err_threshold) {
/* string to hold the path to the log */
char log_file_name[32] = "";
char log_file_path[70] = "";
} else if (write_err_count < write_err_threshold) {
/* string to hold the path to the log */
char log_file_name[32] = "";
char log_file_path[70] = "";
timespec ts;
px4_clock_gettime(CLOCK_REALTIME, &ts);
/* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
time_t gps_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
struct tm tt;
gmtime_r(&gps_time_sec, &tt);
timespec ts;
px4_clock_gettime(CLOCK_REALTIME, &ts);
/* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
time_t gps_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
struct tm tt;
gmtime_r(&gps_time_sec, &tt);
// XXX we do not want to interfere here with the SD log app
strftime(log_file_name, sizeof(log_file_name), "msgs_%Y_%m_%d_%H_%M_%S.txt", &tt);
snprintf(log_file_path, sizeof(log_file_path), PX4_ROOTFSDIR"/fs/microsd/%s", log_file_name);
fp = fopen(log_file_path, "ab");
// XXX we do not want to interfere here with the SD log app
strftime(log_file_name, sizeof(log_file_name), "msgs_%Y_%m_%d_%H_%M_%S.txt", &tt);
snprintf(log_file_path, sizeof(log_file_path), PX4_ROOTFSDIR"/fs/microsd/%s", log_file_name);
fp = fopen(log_file_path, "ab");
if (fp != NULL) {
/* write first message */
fputs(msg.text, fp);
fputs("\n", fp);
}
else {
warn("Failed to open %s errno=%d", log_file_path, errno);
if (fp != NULL) {
/* write first message */
fputs(msg.text, fp);
fputs("\n", fp);
}
else {
warn("Failed to open %s errno=%d", log_file_path, errno);
}
}
}
}
#endif
}
};