aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_main.cpp
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-02-26 22:47:19 +0400
committerAnton Babushkin <anton.babushkin@me.com>2014-02-26 22:47:19 +0400
commit85dc422d9804c894009e37c6eaab67a10c5dca28 (patch)
tree9a2846622200bd4347c95de6ea35fb7b2cc18433 /src/modules/mavlink/mavlink_main.cpp
parentf9619e39341dbc45683c6ccd7e06397f8a537216 (diff)
downloadpx4-firmware-85dc422d9804c894009e37c6eaab67a10c5dca28.tar.gz
px4-firmware-85dc422d9804c894009e37c6eaab67a10c5dca28.tar.bz2
px4-firmware-85dc422d9804c894009e37c6eaab67a10c5dca28.zip
mavlink: more streams implemented, stack size returned to 2048
Diffstat (limited to 'src/modules/mavlink/mavlink_main.cpp')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp26
1 files changed, 10 insertions, 16 deletions
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 <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/home_position.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/position_setpoint_triplet.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/mission.h>
-#include <uORB/topics/mission_result.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
@@ -79,6 +71,10 @@
#include <mathlib/mathlib.h>
#include <mavlink/mavlink_log.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+
#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);