Moved mavlink log to system lib

This commit is contained in:
Lorenz Meier 2013-08-21 14:54:57 +02:00
parent 64b8f5232b
commit 5be2f4a792
4 changed files with 10 additions and 19 deletions

View File

@ -864,7 +864,7 @@ PX4IO::io_set_arming_state()
}
int
PX4IO::io_disable_rc_handling()
PX4IO::disable_rc_handling()
{
return io_disable_rc_handling();
}
@ -1803,7 +1803,7 @@ start(int argc, char *argv[])
/* disable RC handling on request */
if (argc > 0 && !strcmp(argv[0], "norc")) {
if(g_dev->disable_rc_handling())
warnx("Failed disabling RC handling");

View File

@ -39,7 +39,6 @@ MODULE_COMMAND = mavlink
SRCS += mavlink.c \
missionlib.c \
mavlink_parameters.c \
mavlink_log.c \
mavlink_receiver.cpp \
orb_listener.c \
waypoints.c

View File

@ -46,28 +46,25 @@
#include <mavlink/mavlink_log.h>
static FILE* text_recorder_fd = NULL;
void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
__EXPORT void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
{
lb->size = size;
lb->start = 0;
lb->count = 0;
lb->elems = (struct mavlink_logmessage *)calloc(lb->size, sizeof(struct mavlink_logmessage));
text_recorder_fd = fopen("/fs/microsd/text_recorder.txt", "w");
}
int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
__EXPORT int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
{
return lb->count == (int)lb->size;
}
int mavlink_logbuffer_is_empty(struct mavlink_logbuffer *lb)
__EXPORT int mavlink_logbuffer_is_empty(struct mavlink_logbuffer *lb)
{
return lb->count == 0;
}
void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_logmessage *elem)
__EXPORT void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_logmessage *elem)
{
int end = (lb->start + lb->count) % lb->size;
memcpy(&(lb->elems[end]), elem, sizeof(struct mavlink_logmessage));
@ -80,19 +77,13 @@ void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_
}
}
int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem)
__EXPORT int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem)
{
if (!mavlink_logbuffer_is_empty(lb)) {
memcpy(elem, &(lb->elems[lb->start]), sizeof(struct mavlink_logmessage));
lb->start = (lb->start + 1) % lb->size;
--lb->count;
if (text_recorder_fd) {
fwrite(elem->text, 1, strnlen(elem->text, 50), text_recorder_fd);
fputc("\n", text_recorder_fd);
fsync(text_recorder_fd);
}
return 0;
} else {
@ -100,7 +91,7 @@ int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessa
}
}
void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...)
__EXPORT void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);

View File

@ -48,4 +48,5 @@ SRCS = err.c \
geo/geo.c \
systemlib.c \
airspeed.c \
system_params.c
system_params.c \
mavlink_log.c