Browse Source

adjust stack sizes

sbg
Daniel Agar 9 years ago committed by Lorenz Meier
parent
commit
1ecdb0f6fb
  1. 2
      src/drivers/mpu6000/CMakeLists.txt
  2. 1
      src/drivers/ms5611/CMakeLists.txt
  3. 1
      src/drivers/pwm_out_sim/CMakeLists.txt
  4. 2
      src/drivers/pwm_out_sim/pwm_out_sim.cpp
  5. 2
      src/modules/fw_att_control/fw_att_control_main.cpp
  6. 2
      src/modules/mavlink/mavlink_main.cpp
  7. 2
      src/modules/navigator/CMakeLists.txt
  8. 2
      src/modules/sensors/CMakeLists.txt
  9. 2
      src/modules/sensors/sensors.cpp
  10. 2
      src/modules/uORB/CMakeLists.txt

2
src/drivers/mpu6000/CMakeLists.txt

@ -33,7 +33,7 @@ @@ -33,7 +33,7 @@
px4_add_module(
MODULE drivers__mpu6000
MAIN mpu6000
STACK_MAIN 1200
STACK_MAIN 1300
COMPILE_FLAGS
-Weffc++
-Os

1
src/drivers/ms5611/CMakeLists.txt

@ -50,6 +50,7 @@ endif() @@ -50,6 +50,7 @@ endif()
px4_add_module(
MODULE drivers__ms5611
MAIN ms5611
STACK_MAIN 1200
COMPILE_FLAGS
-Os
SRCS ${srcs}

1
src/drivers/pwm_out_sim/CMakeLists.txt

@ -34,6 +34,7 @@ px4_add_module( @@ -34,6 +34,7 @@ px4_add_module(
MODULE drivers__pwm_out_sim
MAIN pwm_out_sim
STACK_MAIN 1200
STACK_MAX 1200
COMPILE_FLAGS
-Os
SRCS

2
src/drivers/pwm_out_sim/pwm_out_sim.cpp

@ -252,7 +252,7 @@ PWMSim::init() @@ -252,7 +252,7 @@ PWMSim::init()
_task = px4_task_spawn_cmd("pwm_out_sim",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
1000,
1200,
(px4_main_t)&PWMSim::task_main_trampoline,
nullptr);

2
src/modules/fw_att_control/fw_att_control_main.cpp

@ -1302,7 +1302,7 @@ FixedwingAttitudeControl::start() @@ -1302,7 +1302,7 @@ FixedwingAttitudeControl::start()
_control_task = px4_task_spawn_cmd("fw_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1300,
1400,
(px4_main_t)&FixedwingAttitudeControl::task_main_trampoline,
nullptr);

2
src/modules/mavlink/mavlink_main.cpp

@ -2286,7 +2286,7 @@ Mavlink::start(int argc, char *argv[]) @@ -2286,7 +2286,7 @@ Mavlink::start(int argc, char *argv[])
px4_task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2800,
3000,
(px4_main_t)&Mavlink::start_helper,
(char *const *)argv);

2
src/modules/navigator/CMakeLists.txt

@ -33,7 +33,7 @@ @@ -33,7 +33,7 @@
px4_add_module(
MODULE modules__navigator
MAIN navigator
STACK_MAIN 1200
STACK_MAIN 1300
COMPILE_FLAGS
-Os
SRCS

2
src/modules/sensors/CMakeLists.txt

@ -35,7 +35,7 @@ px4_add_module( @@ -35,7 +35,7 @@ px4_add_module(
MODULE modules__sensors
MAIN sensors
PRIORITY "SCHED_PRIORITY_MAX-5"
STACK_MAIN 1300
STACK_MAIN 2000
COMPILE_FLAGS
-O3
SRCS

2
src/modules/sensors/sensors.cpp

@ -2276,7 +2276,7 @@ Sensors::start() @@ -2276,7 +2276,7 @@ Sensors::start()
_sensors_task = px4_task_spawn_cmd("sensors",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
2200,
(px4_main_t)&Sensors::task_main_trampoline,
nullptr);

2
src/modules/uORB/CMakeLists.txt

@ -68,7 +68,7 @@ endif() @@ -68,7 +68,7 @@ endif()
px4_add_module(
MODULE modules__uORB
MAIN uorb
STACK_MAIN 2048
STACK_MAIN 2100
COMPILE_FLAGS
-Os
SRCS ${SRCS}

Loading…
Cancel
Save