diff options
Diffstat (limited to 'src')
43 files changed, 91 insertions, 84 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c index aeaf830de..735bdb41a 100644 --- a/src/drivers/ardrone_interface/ardrone_interface.c +++ b/src/drivers/ardrone_interface/ardrone_interface.c @@ -114,7 +114,7 @@ int ardrone_interface_main(int argc, char *argv[]) } thread_should_exit = false; - ardrone_interface_task = task_spawn("ardrone_interface", + ardrone_interface_task = task_spawn_cmd("ardrone_interface", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 15, 2048, diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c index 69edc23ab..212a92cfa 100644 --- a/src/drivers/boards/px4fmu/px4fmu_init.c +++ b/src/drivers/boards/px4fmu/px4fmu_init.c @@ -58,7 +58,7 @@ #include <nuttx/mmcsd.h> #include <nuttx/analog/adc.h> -#include "stm32_internal.h" +#include "stm32.h" #include "px4fmu_internal.h" #include "stm32_uart.h" diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu/px4fmu_internal.h index 671a58f8f..383a046ff 100644 --- a/src/drivers/boards/px4fmu/px4fmu_internal.h +++ b/src/drivers/boards/px4fmu/px4fmu_internal.h @@ -50,7 +50,7 @@ __BEGIN_DECLS /* these headers are not C++ safe */ -#include <stm32_internal.h> +#include <stm32.h> /**************************************************************************************************** diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu/px4fmu_led.c index 34fd194c3..31b25984e 100644 --- a/src/drivers/boards/px4fmu/px4fmu_led.c +++ b/src/drivers/boards/px4fmu/px4fmu_led.c @@ -41,7 +41,7 @@ #include <stdbool.h> -#include "stm32_internal.h" +#include "stm32.h" #include "px4fmu_internal.h" #include <arch/board/board.h> diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c index cb8918306..d85131dd8 100644 --- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c +++ b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c @@ -46,7 +46,7 @@ #include <arch/board/board.h> #include <drivers/drv_pwm_output.h> -#include <stm32_internal.h> +#include <stm32.h> #include <stm32_gpio.h> #include <stm32_tim.h> diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu/px4fmu_spi.c index b5d00eac0..e05ddecf3 100644 --- a/src/drivers/boards/px4fmu/px4fmu_spi.c +++ b/src/drivers/boards/px4fmu/px4fmu_spi.c @@ -52,7 +52,7 @@ #include "up_arch.h" #include "chip.h" -#include "stm32_internal.h" +#include "stm32.h" #include "px4fmu_internal.h" /************************************************************************************ diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu/px4fmu_usb.c index b0b669fbe..0be981c1e 100644 --- a/src/drivers/boards/px4fmu/px4fmu_usb.c +++ b/src/drivers/boards/px4fmu/px4fmu_usb.c @@ -52,7 +52,7 @@ #include <nuttx/usb/usbdev_trace.h> #include "up_arch.h" -#include "stm32_internal.h" +#include "stm32.h" #include "px4fmu_internal.h" /************************************************************************************ diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io/px4io_init.c index d36353c6f..15c59e423 100644 --- a/src/drivers/boards/px4io/px4io_init.c +++ b/src/drivers/boards/px4io/px4io_init.c @@ -54,7 +54,7 @@ #include <nuttx/arch.h> -#include "stm32_internal.h" +#include "stm32.h" #include "px4io_internal.h" #include "stm32_uart.h" diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io/px4io_internal.h index eb2820bb7..6638e715e 100644 --- a/src/drivers/boards/px4io/px4io_internal.h +++ b/src/drivers/boards/px4io/px4io_internal.h @@ -47,7 +47,7 @@ #include <nuttx/compiler.h> #include <stdint.h> -#include <stm32_internal.h> +#include <stm32.h> /************************************************************************************ * Definitions diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io/px4io_pwm_servo.c index a2f73c429..6df470da6 100644 --- a/src/drivers/boards/px4io/px4io_pwm_servo.c +++ b/src/drivers/boards/px4io/px4io_pwm_servo.c @@ -46,7 +46,7 @@ #include <arch/board/board.h> #include <drivers/drv_pwm_output.h> -#include <stm32_internal.h> +#include <stm32.h> #include <stm32_gpio.h> #include <stm32_tim.h> diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h index 92d184326..7e3998fca 100644 --- a/src/drivers/drv_gpio.h +++ b/src/drivers/drv_gpio.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -42,7 +42,7 @@ #include <sys/ioctl.h> -#ifdef CONFIG_ARCH_BOARD_PX4FMU +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 /* * PX4FMU GPIO numbers. * @@ -67,7 +67,7 @@ #endif -#ifdef CONFIG_ARCH_BOARD_PX4IO +#ifdef CONFIG_ARCH_BOARD_PX4IO_V1 /* * PX4IO GPIO numbers. * diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp index d9aa772d4..bd027ce0b 100644 --- a/src/drivers/hil/hil.cpp +++ b/src/drivers/hil/hil.cpp @@ -224,7 +224,7 @@ HIL::init() // gpio_reset(); /* start the HIL interface task */ - _task = task_spawn("fmuhil", + _task = task_spawn_cmd("fmuhil", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2048, diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c index 1d2bdd92e..4699ce5bf 100644 --- a/src/drivers/hott_telemetry/hott_telemetry_main.c +++ b/src/drivers/hott_telemetry/hott_telemetry_main.c @@ -271,7 +271,7 @@ hott_telemetry_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn(daemon_name, + deamon_task = task_spawn_cmd(daemon_name, SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, 2048, diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 80850e708..e62c46b0d 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -109,7 +109,7 @@ int md25_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("md25", + deamon_task = task_spawn_cmd("md25", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 2048, diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index c67276f8a..b54b7aba1 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -313,7 +313,7 @@ MK::init(unsigned motors) gpio_reset(); /* start the IO interface task */ - _task = task_spawn("mkblctrl", + _task = task_spawn_cmd("mkblctrl", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, 2048, diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index bf72892eb..5147ac500 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -239,7 +239,7 @@ PX4FMU::init() gpio_reset(); /* start the IO interface task */ - _task = task_spawn("fmuservo", + _task = task_spawn_cmd("fmuservo", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2048, diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp index 911def943..1020eb946 100644 --- a/src/drivers/stm32/adc/adc.cpp +++ b/src/drivers/stm32/adc/adc.cpp @@ -58,7 +58,7 @@ #include <drivers/drv_adc.h> #include <arch/stm32/chip.h> -#include <stm32_internal.h> +#include <stm32.h> #include <stm32_gpio.h> #include <systemlib/err.h> diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c index fd63681e3..05e1cd8ec 100644 --- a/src/drivers/stm32/drv_hrt.c +++ b/src/drivers/stm32/drv_hrt.c @@ -66,7 +66,7 @@ #include "up_internal.h" #include "up_arch.h" -#include "stm32_internal.h" +#include "stm32.h" #include "stm32_gpio.h" #include "stm32_tim.h" diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c index c1efb8515..7b060412c 100644 --- a/src/drivers/stm32/drv_pwm_servo.c +++ b/src/drivers/stm32/drv_pwm_servo.c @@ -64,7 +64,7 @@ #include <up_internal.h> #include <up_arch.h> -#include <stm32_internal.h> +#include <stm32.h> #include <stm32_gpio.h> #include <stm32_tim.h> diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index ac5511e60..167ef30a8 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -111,7 +111,7 @@ #include <up_internal.h> #include <up_arch.h> -#include <stm32_internal.h> +#include <stm32.h> #include <stm32_gpio.h> #include <stm32_tim.h> diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c index 89fbef020..27888523b 100644 --- a/src/examples/fixedwing_control/main.c +++ b/src/examples/fixedwing_control/main.c @@ -528,7 +528,7 @@ int ex_fixedwing_control_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("ex_fixedwing_control", + deamon_task = task_spawn_cmd("ex_fixedwing_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, 2048, diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c index 4dd5165c8..09065758b 100644 --- a/src/examples/px4_daemon_app/px4_daemon_app.c +++ b/src/examples/px4_daemon_app/px4_daemon_app.c @@ -94,7 +94,7 @@ int px4_daemon_app_main(int argc, char *argv[]) } thread_should_exit = false; - daemon_task = task_spawn("daemon", + daemon_task = task_spawn_cmd("daemon", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp index aebe3d1fe..3b411031a 100644 --- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp +++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp @@ -100,7 +100,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("kalman_demo", + deamon_task = task_spawn_cmd("kalman_demo", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4096, diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp index 8e18c3c9a..7e3eca085 100755 --- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp +++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp @@ -123,7 +123,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[]) } thread_should_exit = false; - attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf", + attitude_estimator_ekf_task = task_spawn_cmd("attitude_estimator_ekf", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 12400, diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c index aab8f3e04..67f053e22 100644 --- a/src/modules/commander/commander.c +++ b/src/modules/commander/commander.c @@ -1200,7 +1200,7 @@ int commander_main(int argc, char *argv[]) } thread_should_exit = false; - daemon_task = task_spawn("commander", + daemon_task = task_spawn_cmd("commander", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, 3000, diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c index 58477632b..6c9c137bb 100644 --- a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c +++ b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c @@ -336,7 +336,7 @@ int fixedwing_att_control_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("fixedwing_att_control", + deamon_task = task_spawn_cmd("fixedwing_att_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, 2048, diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp index e21990c92..e2330427d 100644 --- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp +++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp @@ -107,7 +107,7 @@ int fixedwing_backside_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("control_demo", + deamon_task = task_spawn_cmd("control_demo", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 5120, diff --git a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c index 71c78f5b8..48c0b9f9d 100644 --- a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c +++ b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c @@ -448,7 +448,7 @@ int fixedwing_pos_control_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("fixedwing_pos_control", + deamon_task = task_spawn_cmd("fixedwing_pos_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, 2048, diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index de78cd139..c72a53fee 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -787,7 +787,7 @@ int mavlink_main(int argc, char *argv[]) errx(0, "mavlink already running\n"); thread_should_exit = false; - mavlink_task = task_spawn("mavlink", + mavlink_task = task_spawn_cmd("mavlink", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2048, diff --git a/src/modules/mavlink_onboard/mavlink.c b/src/modules/mavlink_onboard/mavlink.c index 5a2685560..cb6d6b16a 100644 --- a/src/modules/mavlink_onboard/mavlink.c +++ b/src/modules/mavlink_onboard/mavlink.c @@ -495,7 +495,7 @@ int mavlink_onboard_main(int argc, char *argv[]) errx(0, "mavlink already running\n"); thread_should_exit = false; - mavlink_task = task_spawn("mavlink_onboard", + mavlink_task = task_spawn_cmd("mavlink_onboard", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2048, diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c index d94c0a69c..99f25cfe9 100644 --- a/src/modules/multirotor_att_control/multirotor_att_control_main.c +++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c @@ -466,7 +466,7 @@ int multirotor_att_control_main(int argc, char *argv[]) if (!strcmp(argv[1 + optioncount], "start")) { thread_should_exit = false; - mc_task = task_spawn("multirotor_att_control", + mc_task = task_spawn_cmd("multirotor_att_control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 15, 2048, diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c index 7b8d83aa8..f39d11438 100644 --- a/src/modules/multirotor_pos_control/multirotor_pos_control.c +++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c @@ -94,7 +94,7 @@ usage(const char *reason) * Makefile does only apply to this management task. * * The actual stack size should be set in the call - * to task_spawn(). + * to task_spawn_cmd(). */ int multirotor_pos_control_main(int argc, char *argv[]) { @@ -110,7 +110,7 @@ int multirotor_pos_control_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("multirotor pos control", + deamon_task = task_spawn_cmd("multirotor pos control", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 60, 4096, diff --git a/src/modules/position_estimator_mc/position_estimator_mc_main.c b/src/modules/position_estimator_mc/position_estimator_mc_main.c index 10dee3f22..984bd1329 100755 --- a/src/modules/position_estimator_mc/position_estimator_mc_main.c +++ b/src/modules/position_estimator_mc/position_estimator_mc_main.c @@ -123,7 +123,7 @@ int position_estimator_mc_main(int argc, char *argv[]) } thread_should_exit = false; - position_estimator_mc_task = task_spawn("position_estimator_mc", + position_estimator_mc_task = task_spawn_cmd("position_estimator_mc", SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096, diff --git a/src/modules/px4iofirmware/adc.c b/src/modules/px4iofirmware/adc.c index f744698be..81566eb2a 100644 --- a/src/modules/px4iofirmware/adc.c +++ b/src/modules/px4iofirmware/adc.c @@ -41,7 +41,7 @@ #include <nuttx/arch.h> #include <arch/stm32/chip.h> -#include <stm32_internal.h> +#include <stm32.h> #include <drivers/drv_hrt.h> #include <systemlib/perf_counter.h> diff --git a/src/modules/sdlog/sdlog.c b/src/modules/sdlog/sdlog.c index 84a9eb6ac..c22523bf2 100644 --- a/src/modules/sdlog/sdlog.c +++ b/src/modules/sdlog/sdlog.c @@ -161,7 +161,7 @@ bool logging_enabled = true; * Makefile does only apply to this management task. * * The actual stack size should be set in the call - * to task_spawn(). + * to task_spawn_cmd(). */ int sdlog_main(int argc, char *argv[]) { @@ -177,7 +177,7 @@ int sdlog_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn("sdlog", + deamon_task = task_spawn_cmd("sdlog", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 30, 4096, diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 6b6aeedee..8bf5fdbd0 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -1445,7 +1445,7 @@ Sensors::start() ASSERT(_sensors_task == -1); /* start the task */ - _sensors_task = task_spawn("sensors_task", + _sensors_task = task_spawn_cmd("sensors_task", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c index 20b711fa6..8fdff8ac0 100644 --- a/src/modules/systemlib/cpuload.c +++ b/src/modules/systemlib/cpuload.c @@ -1,9 +1,8 @@ /**************************************************************************** - * configs/px4fmu/src/up_leds.c - * arch/arm/src/board/up_leds.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt <gnutt@nuttx.org> + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier <lm@inf.ethz.ch> + * Petri Tanskanen <petri.tanskanen@inf.ethz.ch> * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -15,7 +14,7 @@ * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be + * 3. Neither the name PX4 nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * @@ -34,18 +33,26 @@ * ****************************************************************************/ -/**************************************************************************** - * Included Files - ****************************************************************************/ - +/** + * @file cpuload.c + * + * Measurement of CPU load of each individual task. + * + * @author Lorenz Meier <lm@inf.ethz.ch> + * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch> + */ #include <nuttx/config.h> +#include <nuttx/sched.h> +#include <sys/types.h> #include <stdint.h> #include <stdbool.h> + +#include <arch/arch.h> + #include <debug.h> #include <sys/time.h> -#include <sched.h> #include <arch/board/board.h> #include <drivers/drv_hrt.h> @@ -54,26 +61,13 @@ #ifdef CONFIG_SCHED_INSTRUMENTATION -/**************************************************************************** - * Definitions - ****************************************************************************/ - - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -__EXPORT void sched_note_start(FAR _TCB *tcb); -__EXPORT void sched_note_stop(FAR _TCB *tcb); -__EXPORT void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb); - -/**************************************************************************** - * Name: - ****************************************************************************/ +__EXPORT void sched_note_start(FAR struct tcb_s *tcb); +__EXPORT void sched_note_stop(FAR struct tcb_s *tcb); +__EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb); __EXPORT struct system_load_s system_load; -extern FAR _TCB *sched_gettcb(pid_t pid); +extern FAR struct _TCB *sched_gettcb(pid_t pid); void cpuload_initialize_once() { @@ -109,7 +103,7 @@ void cpuload_initialize_once() // } } -void sched_note_start(FAR _TCB *tcb) +void sched_note_start(FAR struct tcb_s *tcb) { /* search first free slot */ int i; @@ -128,7 +122,7 @@ void sched_note_start(FAR _TCB *tcb) } } -void sched_note_stop(FAR _TCB *tcb) +void sched_note_stop(FAR struct tcb_s *tcb) { int i; @@ -145,7 +139,7 @@ void sched_note_stop(FAR _TCB *tcb) } } -void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb) +void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb) { uint64_t new_time = hrt_absolute_time(); diff --git a/src/modules/systemlib/cpuload.h b/src/modules/systemlib/cpuload.h index a97047ea8..c7aa18d3c 100644 --- a/src/modules/systemlib/cpuload.h +++ b/src/modules/systemlib/cpuload.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -43,7 +43,7 @@ struct system_load_taskinfo_s { uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load uint64_t curr_start_time; ///< Start time of the current scheduling slot uint64_t start_time; ///< FIRST start time of task - FAR struct _TCB *tcb; ///< + FAR struct tcb_s *tcb; ///< bool valid; ///< Task is currently active / valid }; @@ -60,4 +60,6 @@ __EXPORT extern struct system_load_s system_load; __EXPORT void cpuload_initialize_once(void); +__END_DECLS + #endif diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c index daf17ef8b..6c0e876d1 100644 --- a/src/modules/systemlib/err.c +++ b/src/modules/systemlib/err.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -61,7 +61,7 @@ const char * getprogname(void) { #if CONFIG_TASK_NAME_SIZE > 0 - _TCB *thisproc = sched_self(); + FAR struct tcb_s *thisproc = sched_self(); return thisproc->name; #else diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c index afb7eca29..3283aad8a 100644 --- a/src/modules/systemlib/systemlib.c +++ b/src/modules/systemlib/systemlib.c @@ -50,7 +50,7 @@ #include "systemlib.h" -static void kill_task(FAR _TCB *tcb, FAR void *arg); +static void kill_task(FAR struct tcb_s *tcb, FAR void *arg); void killall() { @@ -60,12 +60,12 @@ void killall() sched_foreach(kill_task, NULL); } -static void kill_task(FAR _TCB *tcb, FAR void *arg) +static void kill_task(FAR struct tcb_s *tcb, FAR void *arg) { kill(tcb->pid, SIGUSR1); } -int task_spawn(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[]) +int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[]) { int pid; diff --git a/src/modules/systemlib/systemlib.h b/src/modules/systemlib/systemlib.h index 2c53c648b..0194b5e52 100644 --- a/src/modules/systemlib/systemlib.h +++ b/src/modules/systemlib/systemlib.h @@ -42,11 +42,11 @@ #include <float.h> #include <stdint.h> -__BEGIN_DECLS - /** Reboots the board */ extern void up_systemreset(void) noreturn_function; +__BEGIN_DECLS + /** Sends SIGUSR1 to all processes */ __EXPORT void killall(void); @@ -58,7 +58,7 @@ __EXPORT void killall(void); #endif /** Starts a task and performs any specific accounting, scheduler setup, etc. */ -__EXPORT int task_spawn(const char *name, +__EXPORT int task_spawn_cmd(const char *name, int priority, int scheduler, int stack_size, diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c index 4bcce18fb..7752ffe67 100644 --- a/src/systemcmds/preflight_check/preflight_check.c +++ b/src/systemcmds/preflight_check/preflight_check.c @@ -146,6 +146,15 @@ int preflight_check_main(int argc, char *argv[]) bool rc_ok = true; char nbuf[20]; + /* first check channel mappings */ + /* check which map param applies */ + // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) { + // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1); + // /* give system time to flush error message in case there are more */ + // usleep(100000); + // count++; + // } + for (int i = 0; i < 12; i++) { /* should the channel be enabled? */ uint8_t count = 0; @@ -209,8 +218,8 @@ int preflight_check_main(int argc, char *argv[]) count++; } - /* XXX needs inspection of all the _MAP params */ - // if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= MAX_CONTROL_CHANNELS) { + /* check which map param applies */ + // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) { // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1); // /* give system time to flush error message in case there are more */ // usleep(100000); diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c index 59d2bc8f1..efe62685c 100644 --- a/src/systemcmds/top/top.c +++ b/src/systemcmds/top/top.c @@ -1,7 +1,7 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Lorenz Meier <lm@inf.ethz.ch> + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier <lm@inf.ethz.ch> * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -36,6 +36,8 @@ * @file top.c * Tool similar to UNIX top command * @see http://en.wikipedia.org/wiki/Top_unix + * + * @author Lorenz Meier <lm@inf.ethz.ch> */ #include <nuttx/config.h> |