From 85dc422d9804c894009e37c6eaab67a10c5dca28 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 26 Feb 2014 22:47:19 +0400 Subject: mavlink: more streams implemented, stack size returned to 2048 --- src/modules/mavlink/mavlink_main.cpp | 26 ++++++++++---------------- 1 file changed, 10 insertions(+), 16 deletions(-) (limited to 'src/modules/mavlink/mavlink_main.cpp') diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 33d81729c..5ac76e1cf 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -61,14 +61,6 @@ #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include #include #include @@ -79,6 +71,10 @@ #include #include +#include +#include +#include + #include "mavlink_bridge_header.h" #include "mavlink_main.h" #include "mavlink_messages.h" @@ -1542,13 +1538,11 @@ Mavlink::task_main(int argc, char *argv[]) add_stream("HEARTBEAT", 1.0f); add_stream("SYS_STATUS", 1.0f); - add_stream("HIGHRES_IMU", 20.0f); -// add_stream("RAW_IMU", 10.0f); - add_stream("ATTITUDE", 20.0f); -// add_stream("NAMED_VALUE_FLOAT", 5.0f); -// add_stream("SERVO_OUTPUT_RAW", 2.0f); -// add_stream("GPS_RAW_INT", 2.0f); -// add_stream("MANUAL_CONTROL", 2.0f); + add_stream("HIGHRES_IMU", 1.0f); + add_stream("ATTITUDE", 10.0f); + add_stream("GPS_RAW_INT", 1.0f); + add_stream("GLOBAL_POSITION_INT", 5.0f); + add_stream("LOCAL_POSITION_NED", 5.0f); while (!_task_should_exit) { /* main loop */ @@ -1656,7 +1650,7 @@ Mavlink::start(int argc, char *argv[]) /*mavlink->_mavlink_task = */task_spawn_cmd(buf, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 4096, + 2048, (main_t)&Mavlink::start_helper, (const char **)argv); -- cgit v1.2.3