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.
This commit is contained in:
px4dev 2012-10-03 23:13:20 -07:00
parent 216aa20ac2
commit dfae108e6a
15 changed files with 22 additions and 16 deletions

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -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, &param);
/* XXX do any other private task accounting here */
/* XXX do any other private task accounting here before the task starts */
}
sched_unlock();
return pid;

View File

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

View File

@ -546,7 +546,7 @@ CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
CONFIG_MSEC_PER_TICK=1
CONFIG_RR_INTERVAL=1
CONFIG_RR_INTERVAL=0
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_START_YEAR=1970