mavlink: change message buffer size to 4

This commit is contained in:
Thomas Gubler
2014-09-30 16:00:14 +02:00
parent 5452732610
commit 2766285d56
+2 -2
View File
@@ -1328,7 +1328,7 @@ Mavlink::task_main(int argc, char *argv[])
* make space for two messages plus off-by-one space as we use the empty element
* marker ring buffer approach.
*/
if (OK != message_buffer_init(10 * sizeof(mavlink_message_t) + 1)) {
if (OK != message_buffer_init(4 * sizeof(mavlink_message_t) + 1)) {
errx(1, "can't allocate message buffer, exiting");
}
@@ -1382,7 +1382,7 @@ Mavlink::task_main(int argc, char *argv[])
_mission_manager->set_verbose(_verbose);
LL_APPEND(_streams, _mission_manager);
switch (_mode) {
case MAVLINK_MODE_NORMAL: