diff options
author | px4dev <px4@purgatory.org> | 2012-10-03 23:13:20 -0700 |
---|---|---|
committer | px4dev <px4@purgatory.org> | 2012-10-03 23:13:20 -0700 |
commit | dfae108e6aff6e77eb05def50d99fb5c6d2c28c8 (patch) | |
tree | 57478848a3c87b66978eef5ae986882aed93b598 /apps | |
parent | 216aa20ac278c55931d618bb2ebf8b7bc1a3614b (diff) | |
download | px4-firmware-dfae108e6aff6e77eb05def50d99fb5c6d2c28c8.tar.gz px4-firmware-dfae108e6aff6e77eb05def50d99fb5c6d2c28c8.tar.bz2 px4-firmware-dfae108e6aff6e77eb05def50d99fb5c6d2c28c8.zip |
Go back to the FIFO scheduler for now, as we don't have time to shake out the RR scheduler changeover just yet.
Make the "default" scheduler a centralized definition so that changes are easier in future.
Diffstat (limited to 'apps')
-rw-r--r-- | apps/ardrone_interface/ardrone_interface.c | 2 | ||||
-rw-r--r-- | apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c | 2 | ||||
-rw-r--r-- | apps/commander/commander.c | 2 | ||||
-rw-r--r-- | apps/examples/px4_deamon_app/px4_deamon_app.c | 2 | ||||
-rw-r--r-- | apps/fixedwing_control/fixedwing_control.c | 2 | ||||
-rw-r--r-- | apps/gps/gps.c | 2 | ||||
-rw-r--r-- | apps/mavlink/mavlink.c | 2 | ||||
-rw-r--r-- | apps/multirotor_att_control/multirotor_att_control_main.c | 2 | ||||
-rw-r--r-- | apps/px4/fmu/fmu.cpp | 2 | ||||
-rw-r--r-- | apps/sdlog/sdlog.c | 4 | ||||
-rw-r--r-- | apps/sensors/sensors.cpp | 2 | ||||
-rw-r--r-- | apps/systemcmds/led/led.c | 2 | ||||
-rw-r--r-- | apps/systemlib/systemlib.c | 3 | ||||
-rw-r--r-- | apps/systemlib/systemlib.h | 7 |
14 files changed, 21 insertions, 15 deletions
diff --git a/apps/ardrone_interface/ardrone_interface.c b/apps/ardrone_interface/ardrone_interface.c index 74b32c4af..8d4a473b6 100644 --- a/apps/ardrone_interface/ardrone_interface.c +++ b/apps/ardrone_interface/ardrone_interface.c @@ -115,7 +115,7 @@ int ardrone_interface_main(int argc, char *argv[]) thread_should_exit = false; ardrone_interface_task = task_spawn("ardrone_interface", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 15, 4096, ardrone_interface_thread_main, diff --git a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c index 41f469ae4..d2e0efb56 100644 --- a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c +++ b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c @@ -159,7 +159,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[]) thread_should_exit = false; attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 20000, attitude_estimator_ekf_thread_main, diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 77e4da850..16f74f43c 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -950,7 +950,7 @@ int commander_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn("commander", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 50, 4096, commander_thread_main, diff --git a/apps/examples/px4_deamon_app/px4_deamon_app.c b/apps/examples/px4_deamon_app/px4_deamon_app.c index 6068df5a3..6eb046d45 100644 --- a/apps/examples/px4_deamon_app/px4_deamon_app.c +++ b/apps/examples/px4_deamon_app/px4_deamon_app.c @@ -92,7 +92,7 @@ int px4_deamon_app_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn("deamon", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, px4_deamon_thread_main, diff --git a/apps/fixedwing_control/fixedwing_control.c b/apps/fixedwing_control/fixedwing_control.c index 470d963af..ad08247e1 100644 --- a/apps/fixedwing_control/fixedwing_control.c +++ b/apps/fixedwing_control/fixedwing_control.c @@ -416,7 +416,7 @@ int fixedwing_control_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn("fixedwing_control", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, 4096, fixedwing_control_thread_main, diff --git a/apps/gps/gps.c b/apps/gps/gps.c index 8304c72e1..b26b09f95 100644 --- a/apps/gps/gps.c +++ b/apps/gps/gps.c @@ -143,7 +143,7 @@ int gps_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn("gps", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 4096, gps_thread_main, diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index b0cf01fd4..cec2593c1 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -1872,7 +1872,7 @@ int mavlink_main(int argc, char *argv[]) thread_should_exit = false; mavlink_task = task_spawn("mavlink", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 6000, mavlink_thread_main, diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c index 72566a43c..5e492268e 100644 --- a/apps/multirotor_att_control/multirotor_att_control_main.c +++ b/apps/multirotor_att_control/multirotor_att_control_main.c @@ -353,7 +353,7 @@ int multirotor_att_control_main(int argc, char *argv[]) thread_should_exit = false; mc_task = task_spawn("multirotor_att_control", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 15, 4096, mc_thread_main, diff --git a/apps/px4/fmu/fmu.cpp b/apps/px4/fmu/fmu.cpp index eeef2f914..18f27d49e 100644 --- a/apps/px4/fmu/fmu.cpp +++ b/apps/px4/fmu/fmu.cpp @@ -172,7 +172,7 @@ FMUServo::init() /* start the IO interface task */ _task = task_spawn("fmuservo", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1024, (main_t)&FMUServo::task_main_trampoline, diff --git a/apps/sdlog/sdlog.c b/apps/sdlog/sdlog.c index 0426dfb9c..22b8d82ee 100644 --- a/apps/sdlog/sdlog.c +++ b/apps/sdlog/sdlog.c @@ -109,7 +109,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_create(). + * to task_spawn(). */ int sdlog_main(int argc, char *argv[]) { @@ -126,7 +126,7 @@ int sdlog_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn("sdlog", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 30, 4096, sdlog_thread_main, diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index b9de42f76..7106edc6b 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -1174,7 +1174,7 @@ Sensors::start() /* start the task */ _sensors_task = task_spawn("sensors_task", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 6000, /* XXX may be excesssive */ (main_t)&Sensors::task_main_trampoline, diff --git a/apps/systemcmds/led/led.c b/apps/systemcmds/led/led.c index da0d99964..02c1bb133 100644 --- a/apps/systemcmds/led/led.c +++ b/apps/systemcmds/led/led.c @@ -148,7 +148,7 @@ int led_main(int argc, char *argv[]) thread_should_exit = false; led_task = task_spawn("led", - SCHED_RR, + SCHED_DEFAULT, SCHED_PRIORITY_MAX - 15, 4096, led_thread_main, diff --git a/apps/systemlib/systemlib.c b/apps/systemlib/systemlib.c index 3d46a17a8..94a5283f0 100644 --- a/apps/systemlib/systemlib.c +++ b/apps/systemlib/systemlib.c @@ -138,9 +138,8 @@ int task_spawn(const char *name, int scheduler, int priority, int stack_size, ma param.sched_priority = priority; sched_setscheduler(pid, scheduler, ¶m); - /* XXX do any other private task accounting here */ + /* XXX do any other private task accounting here before the task starts */ } - sched_unlock(); return pid; diff --git a/apps/systemlib/systemlib.h b/apps/systemlib/systemlib.h index da1524435..997f40ded 100644 --- a/apps/systemlib/systemlib.h +++ b/apps/systemlib/systemlib.h @@ -50,6 +50,13 @@ __EXPORT int reboot(void); /** Sends SIGUSR1 to all processes */ __EXPORT void killall(void); +/** Default scheduler type */ +#if CONFIG_RR_INTERVAL > 0 +# define SCHED_DEFAULT SCHED_RR +#else +# define SCHED_DEFAULT SCHED_FIFO +#endif + /** Starts a task and performs any specific accounting, scheduler setup, etc. */ __EXPORT int task_spawn(const char *name, int priority, |