@ -33,7 +33,7 @@
px4_add_module(
MODULE drivers__mpu6000
MAIN mpu6000
STACK_MAIN 1200
STACK_MAIN 1300
COMPILE_FLAGS
-Weffc++
-Os
@ -50,6 +50,7 @@ endif()
MODULE drivers__ms5611
MAIN ms5611
SRCS ${srcs}
@ -34,6 +34,7 @@ px4_add_module(
MODULE drivers__pwm_out_sim
MAIN pwm_out_sim
STACK_MAX 1200
SRCS
@ -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);
@ -1302,7 +1302,7 @@ FixedwingAttitudeControl::start()
_control_task = px4_task_spawn_cmd("fw_att_control",
SCHED_PRIORITY_MAX - 5,
1300,
1400,
(px4_main_t)&FixedwingAttitudeControl::task_main_trampoline,
@ -2286,7 +2286,7 @@ Mavlink::start(int argc, char *argv[])
px4_task_spawn_cmd(buf,
2800,
3000,
(px4_main_t)&Mavlink::start_helper,
(char *const *)argv);
MODULE modules__navigator
MAIN navigator
@ -35,7 +35,7 @@ px4_add_module(
MODULE modules__sensors
MAIN sensors
PRIORITY "SCHED_PRIORITY_MAX-5"
STACK_MAIN 2000
-O3
@ -2276,7 +2276,7 @@ Sensors::start()
_sensors_task = px4_task_spawn_cmd("sensors",
2000,
2200,
(px4_main_t)&Sensors::task_main_trampoline,
@ -68,7 +68,7 @@ endif()
MODULE modules__uORB
MAIN uorb
STACK_MAIN 2048
STACK_MAIN 2100
SRCS ${SRCS}