aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-01-30 00:54:55 -0800
committerLorenz Meier <lm@inf.ethz.ch>2014-01-30 00:54:55 -0800
commit3b31a6b1b9756eb191eaaafb1c137e6874079281 (patch)
tree359f2caf74e019ea452c3b0fdc17a8643bc42651 /src
parent70afb3ca3b3f1844241c9c9312579bbb2475232c (diff)
parent44cb4d96171fae0bcd5dd4bdf5cb668a039727b5 (diff)
downloadpx4-firmware-3b31a6b1b9756eb191eaaafb1c137e6874079281.tar.gz
px4-firmware-3b31a6b1b9756eb191eaaafb1c137e6874079281.tar.bz2
px4-firmware-3b31a6b1b9756eb191eaaafb1c137e6874079281.zip
Merge pull request #620 from pigeonhunter/stack_sizes
Stack sizes
Diffstat (limited to 'src')
-rw-r--r--src/drivers/gps/gps.cpp2
-rw-r--r--src/drivers/px4io/px4io.cpp2
-rw-r--r--src/modules/commander/commander.cpp4
-rw-r--r--src/modules/mavlink/mavlink.c2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
-rw-r--r--src/modules/mavlink/orb_listener.c2
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
8 files changed, 9 insertions, 9 deletions
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 6b72d560f..f2faf711b 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -209,7 +209,7 @@ GPS::init()
goto out;
/* start the GPS driver worker task */
- _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
+ _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 1280, (main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
warnx("task start failed: %d", errno);
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 9595518ec..ed75d7680 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -759,7 +759,7 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 1024, (main_t)&PX4IO::task_main_trampoline, nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index add7312de..33589940c 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -237,7 +237,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 3000,
+ 2088,
commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -648,7 +648,7 @@ int commander_thread_main(int argc, char *argv[])
pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr);
- pthread_attr_setstacksize(&commander_low_prio_attr, 2992);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 1728);
struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 20853379d..ebf01a2f4 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -773,7 +773,7 @@ int mavlink_main(int argc, char *argv[])
mavlink_task = task_spawn_cmd("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1200,
mavlink_thread_main,
(const char **)argv);
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 7b6fad658..9fc7b748a 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -871,7 +871,7 @@ receive_start(int uart)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 3000);
+ pthread_attr_setstacksize(&receiveloop_attr, 1816);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index e1dabfd21..bfb824db7 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -838,7 +838,7 @@ uorb_receive_start(void)
pthread_attr_init(&uorb_attr);
/* Set stack size, needs less than 2k */
- pthread_attr_setstacksize(&uorb_attr, 2048);
+ pthread_attr_setstacksize(&uorb_attr, 1648);
pthread_t thread;
pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL);
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 3d23d0c09..a89c7eace 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -126,7 +126,7 @@ int multirotor_pos_control_main(int argc, char *argv[])
deamon_task = task_spawn_cmd("multirotor_pos_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 60,
- 4096,
+ 2408,
multirotor_pos_control_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 3084b6d92..eb5a23b69 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -128,7 +128,7 @@ int position_estimator_inav_main(int argc, char *argv[])
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
- SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096,
+ SCHED_RR, SCHED_PRIORITY_MAX - 5, 2568,
position_estimator_inav_thread_main,
(argv) ? (const char **) &argv[2] : (const char **) NULL);
exit(0);