diff options
Diffstat (limited to 'src')
27 files changed, 60 insertions, 14 deletions
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk index 05bc7a5b3..eeb59e1a1 100644 --- a/src/drivers/px4fmu/module.mk +++ b/src/drivers/px4fmu/module.mk @@ -4,3 +4,5 @@ MODULE_COMMAND = fmu SRCS = fmu.cpp + +MODULE_STACKSIZE = 1200 diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk index 2054faa12..c14f1f783 100644 --- a/src/drivers/px4io/module.mk +++ b/src/drivers/px4io/module.mk @@ -44,3 +44,5 @@ SRCS = px4io.cpp \ # XXX prune to just get UART registers INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common + +MODULE_STACKSIZE = 1200 diff --git a/src/examples/fixedwing_control/module.mk b/src/examples/fixedwing_control/module.mk index d2c48934f..a2a9eb113 100644 --- a/src/examples/fixedwing_control/module.mk +++ b/src/examples/fixedwing_control/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = ex_fixedwing_control SRCS = main.c \ params.c + +MODULE_STACKSIZE = 1200 diff --git a/src/examples/px4_daemon_app/module.mk b/src/examples/px4_daemon_app/module.mk index 5f8aa73d5..fc4223142 100644 --- a/src/examples/px4_daemon_app/module.mk +++ b/src/examples/px4_daemon_app/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = px4_daemon_app SRCS = px4_daemon_app.c + +MODULE_STACKSIZE = 1200 diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index 53f1b4a9a..3eaf14148 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -98,7 +98,7 @@ int px4_daemon_app_main(int argc, char *argv[]) daemon_task = task_spawn_cmd("daemon", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 4096, + 2000, px4_daemon_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); diff --git a/src/examples/px4_mavlink_debug/module.mk b/src/examples/px4_mavlink_debug/module.mk index fefd61496..c7ef97fc4 100644 --- a/src/examples/px4_mavlink_debug/module.mk +++ b/src/examples/px4_mavlink_debug/module.mk @@ -37,4 +37,6 @@ MODULE_COMMAND = px4_mavlink_debug -SRCS = px4_mavlink_debug.c
\ No newline at end of file +SRCS = px4_mavlink_debug.c + +MODULE_STACKSIZE = 2000 diff --git a/src/modules/attitude_estimator_ekf/module.mk b/src/modules/attitude_estimator_ekf/module.mk index d98647f99..99d0c5bf2 100644 --- a/src/modules/attitude_estimator_ekf/module.mk +++ b/src/modules/attitude_estimator_ekf/module.mk @@ -50,3 +50,5 @@ SRCS = attitude_estimator_ekf_main.cpp \ codegen/rtGetNaN.c \ codegen/norm.c \ codegen/cross.c + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/attitude_estimator_so3/module.mk b/src/modules/attitude_estimator_so3/module.mk index e29bb16a6..f52715abb 100644 --- a/src/modules/attitude_estimator_so3/module.mk +++ b/src/modules/attitude_estimator_so3/module.mk @@ -6,3 +6,5 @@ MODULE_COMMAND = attitude_estimator_so3 SRCS = attitude_estimator_so3_main.cpp \ attitude_estimator_so3_params.c + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 17d3d3dcd..13da27dcd 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -249,7 +249,7 @@ int commander_main(int argc, char *argv[]) daemon_task = task_spawn_cmd("commander", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, - 3000, + 2950, commander_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); @@ -743,7 +743,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, 2900); struct sched_param param; (void)pthread_attr_getschedparam(&commander_low_prio_attr, ¶m); diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 9296db6ed..0ead22f77 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -72,7 +72,7 @@ int do_mag_calibration(int mavlink_fd) uint64_t calibration_interval = 45 * 1000 * 1000; /* maximum 500 values */ - const unsigned int calibration_maxcount = 500; + const unsigned int calibration_maxcount = 240; unsigned int calibration_counter; struct mag_scale mscale_null = { @@ -121,6 +121,20 @@ int do_mag_calibration(int mavlink_fd) if (x == NULL || y == NULL || z == NULL) { mavlink_log_critical(mavlink_fd, "ERROR: out of memory"); + + /* clean up */ + if (x != NULL) { + free(x); + } + + if (y != NULL) { + free(y); + } + + if (z != NULL) { + free(z); + } + res = ERROR; return res; } diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk index 27670dd3f..234607b3d 100644 --- a/src/modules/dataman/module.mk +++ b/src/modules/dataman/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = dataman SRCS = dataman.c + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index dd88b0949..3e44102fb 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1523,6 +1523,8 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) void Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg) { + uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN]; + uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg); mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len); @@ -2193,7 +2195,7 @@ Mavlink::start(int argc, char *argv[]) task_spawn_cmd(buf, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 2048, + 2000, (main_t)&Mavlink::start_helper, (const char **)argv); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 1bf51fd31..c7a7d32f8 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -237,7 +237,6 @@ private: orb_advert_t _mission_pub; struct mission_s mission; - uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN]; MAVLINK_MODE _mode; uint8_t _mavlink_wpm_comp_id; diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk index dcca11977..f532e26fe 100644 --- a/src/modules/mavlink/module.mk +++ b/src/modules/mavlink/module.mk @@ -48,3 +48,5 @@ SRCS += mavlink_main.cpp \ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1024 diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 74e31dd5b..9a0b726d4 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -818,7 +818,7 @@ MulticopterAttitudeControl::start() _control_task = task_spawn_cmd("mc_att_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 2048, + 2000, (main_t)&MulticopterAttitudeControl::task_main_trampoline, nullptr); diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 6e611d4ab..09960d106 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -1062,7 +1062,7 @@ MulticopterPositionControl::start() _control_task = task_spawn_cmd("mc_pos_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 2048, + 2000, (main_t)&MulticopterPositionControl::task_main_trampoline, nullptr); diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk index 55f8a4caa..6ea9dec2b 100644 --- a/src/modules/navigator/module.mk +++ b/src/modules/navigator/module.mk @@ -45,3 +45,5 @@ SRCS = navigator_main.cpp \ geofence_params.c INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index c6b5112a5..87c893079 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -848,7 +848,7 @@ Navigator::start() _navigator_task = task_spawn_cmd("navigator", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 2048, + 2000, (main_t)&Navigator::task_main_trampoline, nullptr); diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk index f53129688..a28d43e72 100644 --- a/src/modules/sdlog2/module.mk +++ b/src/modules/sdlog2/module.mk @@ -41,3 +41,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30" SRCS = sdlog2.c \ logbuffer.c + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk index aa538fd6b..5b1bc5e86 100644 --- a/src/modules/sensors/module.mk +++ b/src/modules/sensors/module.mk @@ -40,3 +40,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5" SRCS = sensors.cpp \ sensor_params.c + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 18bf97f8d..8da6b06ef 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -1669,7 +1669,7 @@ Sensors::start() _sensors_task = task_spawn_cmd("sensors_task", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 2048, + 2000, (main_t)&Sensors::task_main_trampoline, nullptr); diff --git a/src/systemcmds/param/module.mk b/src/systemcmds/param/module.mk index 63f15ad28..f716eb71e 100644 --- a/src/systemcmds/param/module.mk +++ b/src/systemcmds/param/module.mk @@ -38,7 +38,8 @@ MODULE_COMMAND = param SRCS = param.c -MODULE_STACKSIZE = 4096 +# Note: measurements yielded a max of 900 bytes used. +MODULE_STACKSIZE = 1800 MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/perf/module.mk b/src/systemcmds/perf/module.mk index 77952842b..ec39a7a85 100644 --- a/src/systemcmds/perf/module.mk +++ b/src/systemcmds/perf/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = perf SRCS = perf.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1800 diff --git a/src/systemcmds/preflight_check/module.mk b/src/systemcmds/preflight_check/module.mk index 7c3c88783..0cb2a4cd0 100644 --- a/src/systemcmds/preflight_check/module.mk +++ b/src/systemcmds/preflight_check/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = preflight_check SRCS = preflight_check.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1800 diff --git a/src/systemcmds/pwm/module.mk b/src/systemcmds/pwm/module.mk index 4a23bba90..13a24150f 100644 --- a/src/systemcmds/pwm/module.mk +++ b/src/systemcmds/pwm/module.mk @@ -38,4 +38,4 @@ MODULE_COMMAND = pwm SRCS = pwm.c -MODULE_STACKSIZE = 4096 +MODULE_STACKSIZE = 1800 diff --git a/src/systemcmds/reboot/module.mk b/src/systemcmds/reboot/module.mk index 19f64af54..edf9d8b37 100644 --- a/src/systemcmds/reboot/module.mk +++ b/src/systemcmds/reboot/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = reboot SRCS = reboot.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 800 diff --git a/src/systemcmds/top/module.mk b/src/systemcmds/top/module.mk index 985ea846f..548a09f85 100644 --- a/src/systemcmds/top/module.mk +++ b/src/systemcmds/top/module.mk @@ -38,7 +38,7 @@ MODULE_COMMAND = top SRCS = top.c -MODULE_STACKSIZE = 2048 +MODULE_STACKSIZE = 1700 MAXOPTIMIZATION = -Os |