mavlink_log: enable queueing

We don't want to drop messages if possible for mavlink log messages, so
let's use the orb queueing.
This commit is contained in:
Julian Oes 2016-07-12 13:50:54 +02:00
parent 314ee6b7e0
commit 8ded6a58ab

View File

@ -47,6 +47,7 @@
#include <uORB/topics/mavlink_log.h>
#include "mavlink_log.h"
#define MAVLINK_LOG_QUEUE_SIZE 5
__EXPORT void mavlink_vasprintf(int severity, orb_advert_t *mavlink_log_pub, const char *fmt, ...)
@ -79,7 +80,9 @@ __EXPORT void mavlink_vasprintf(int severity, orb_advert_t *mavlink_log_pub, con
orb_publish(ORB_ID(mavlink_log), *mavlink_log_pub, &log_msg);
} else {
*mavlink_log_pub = orb_advertise(ORB_ID(mavlink_log), &log_msg);
*mavlink_log_pub = orb_advertise_queue(ORB_ID(mavlink_log),
&log_msg,
MAVLINK_LOG_QUEUE_SIZE);
}
}