aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-02-27 11:23:44 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-03-01 18:32:07 +0100
commit0ebbb5f533b969a1de32dcb4d2a87a0e9fea74d2 (patch)
tree481d8928a9128b3bbb8123f171d59432494a7cfe
parentda5b06a5df475b853368a895e92d80a1c1406d28 (diff)
downloadpx4-firmware-0ebbb5f533b969a1de32dcb4d2a87a0e9fea74d2.tar.gz
px4-firmware-0ebbb5f533b969a1de32dcb4d2a87a0e9fea74d2.tar.bz2
px4-firmware-0ebbb5f533b969a1de32dcb4d2a87a0e9fea74d2.zip
MAVLink: Use less RAM
-rw-r--r--src/modules/mavlink/mavlink_main.cpp2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
2 files changed, 2 insertions, 2 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 024dfd6fb..0132a3193 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1621,7 +1621,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2800,
+ 2700,
(main_t)&Mavlink::start_helper,
(char * const *)argv);
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 573d5aecf..0c34fc58a 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -1549,7 +1549,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
param.sched_priority = SCHED_PRIORITY_MAX - 80;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 2900);
+ pthread_attr_setstacksize(&receiveloop_attr, 2100);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);