aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-05-15 00:14:33 -0700
committerLorenz Meier <lm@inf.ethz.ch>2014-05-15 00:14:33 -0700
commit91b67d3f4aff0686638828ed2629793cc04b8be4 (patch)
treec91b27ae568cc0f9286f97bd7743b60861921633 /src/modules
parent839373f5aebe462e55533c0e8a0b960de46d4c24 (diff)
parent9f097c1858d002eecbcda8cf8272fb8fbde1a31e (diff)
downloadpx4-firmware-91b67d3f4aff0686638828ed2629793cc04b8be4.tar.gz
px4-firmware-91b67d3f4aff0686638828ed2629793cc04b8be4.tar.bz2
px4-firmware-91b67d3f4aff0686638828ed2629793cc04b8be4.zip
Merge pull request #954 from PX4/stack_sweep
Stack sweep
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/attitude_estimator_ekf/module.mk2
-rw-r--r--src/modules/attitude_estimator_so3/module.mk2
-rw-r--r--src/modules/commander/commander.cpp4
-rw-r--r--src/modules/commander/mag_calibration.cpp16
-rw-r--r--src/modules/dataman/module.mk2
-rw-r--r--src/modules/mavlink/mavlink_main.cpp4
-rw-r--r--src/modules/mavlink/mavlink_main.h1
-rw-r--r--src/modules/mavlink/module.mk2
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp2
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp2
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/navigator/navigator_main.cpp2
-rw-r--r--src/modules/sdlog2/module.mk2
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensors.cpp2
15 files changed, 38 insertions, 9 deletions
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, &param);
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);