Merge pull request #954 from PX4/stack_sweep

Stack sweep
This commit is contained in:
Lorenz Meier 2014-05-15 00:14:33 -07:00
commit 91b67d3f4a
29 changed files with 68 additions and 18 deletions

View File

@ -8,7 +8,7 @@ then
if ver hwcmp PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
sdlog2 start -r 50 -a -b 8 -t
sdlog2 start -r 50 -a -b 5 -t
else
echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 16 -t

View File

@ -3,16 +3,20 @@
# USB MAVLink start
#
echo "Starting MAVLink on this USB console"
mavlink start -r 10000 -d /dev/ttyACM0
# Enable a number of interesting streams we want via USB
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
# Exit shell to make it available to MAVLink
exit

View File

@ -4,3 +4,5 @@
MODULE_COMMAND = fmu
SRCS = fmu.cpp
MODULE_STACKSIZE = 1200

View File

@ -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

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = ex_fixedwing_control
SRCS = main.c \
params.c
MODULE_STACKSIZE = 1200

View File

@ -38,3 +38,5 @@
MODULE_COMMAND = px4_daemon_app
SRCS = px4_daemon_app.c
MODULE_STACKSIZE = 1200

View File

@ -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);

View File

@ -37,4 +37,6 @@
MODULE_COMMAND = px4_mavlink_debug
SRCS = px4_mavlink_debug.c
SRCS = px4_mavlink_debug.c
MODULE_STACKSIZE = 2000

View File

@ -50,3 +50,5 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/rtGetNaN.c \
codegen/norm.c \
codegen/cross.c
MODULE_STACKSIZE = 1200

View File

@ -6,3 +6,5 @@ MODULE_COMMAND = attitude_estimator_so3
SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c
MODULE_STACKSIZE = 1200

View File

@ -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);

View File

@ -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;
}

View File

@ -38,3 +38,5 @@
MODULE_COMMAND = dataman
SRCS = dataman.c
MODULE_STACKSIZE = 1200

View File

@ -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);

View File

@ -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;

View File

@ -48,3 +48,5 @@ SRCS += mavlink_main.cpp \
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1024

View File

@ -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);

View File

@ -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);

View File

@ -45,3 +45,5 @@ SRCS = navigator_main.cpp \
geofence_params.c
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200

View File

@ -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);

View File

@ -41,3 +41,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
SRCS = sdlog2.c \
logbuffer.c
MODULE_STACKSIZE = 1200

View File

@ -40,3 +40,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
SRCS = sensors.cpp \
sensor_params.c
MODULE_STACKSIZE = 1200

View File

@ -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);

View File

@ -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

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = perf
SRCS = perf.c
MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1800

View File

@ -40,3 +40,5 @@ MODULE_COMMAND = preflight_check
SRCS = preflight_check.c
MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1800

View File

@ -38,4 +38,4 @@
MODULE_COMMAND = pwm
SRCS = pwm.c
MODULE_STACKSIZE = 4096
MODULE_STACKSIZE = 1800

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = reboot
SRCS = reboot.c
MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 800

View File

@ -38,7 +38,7 @@
MODULE_COMMAND = top
SRCS = top.c
MODULE_STACKSIZE = 2048
MODULE_STACKSIZE = 1700
MAXOPTIMIZATION = -Os