AP_HAL_Linux: remove support for timesliced timer

This has long been replaced by the bus per thread scheme.
This commit is contained in:
Lucas De Marchi 2017-07-31 12:28:25 -07:00
parent 13dbc306e1
commit 0a158f6d3f
2 changed files with 2 additions and 81 deletions

View File

@ -195,66 +195,10 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
bool Scheduler::register_timer_process(AP_HAL::MemberProc proc, bool Scheduler::register_timer_process(AP_HAL::MemberProc proc,
uint8_t freq_div) uint8_t freq_div)
{ {
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
if (freq_div > 1) {
return _register_timesliced_proc(proc, freq_div);
}
/* fallback to normal timer process */
#endif
register_timer_process(proc); register_timer_process(proc);
return false; return false;
} }
bool Scheduler::_register_timesliced_proc(AP_HAL::MemberProc proc,
uint8_t freq_div)
{
unsigned int i, j;
uint8_t distance, min_distance, best_distance;
uint8_t best_timeslot;
if (_num_timesliced_procs > LINUX_SCHEDULER_MAX_TIMESLICED_PROCS) {
hal.console->printf("Out of timesliced processes\n");
return false;
}
/* if max_freq_div increases, update the timeslots accordingly */
if (freq_div > _max_freq_div) {
for (i = 0; i < _num_timesliced_procs; i++) {
_timesliced_proc[i].timeslot = _timesliced_proc[i].timeslot
/ _max_freq_div * freq_div;
}
_max_freq_div = freq_div;
}
best_distance = 0;
best_timeslot = 0;
/* Look for the timeslot that maximizes the min distance with other timeslots */
for (i = 0; i < _max_freq_div; i++) {
min_distance = _max_freq_div;
for (j = 0; j < _num_timesliced_procs; j++) {
distance = std::min(i - _timesliced_proc[j].timeslot,
_max_freq_div + _timesliced_proc[j].timeslot - i);
if (distance < min_distance) {
min_distance = distance;
if (min_distance == 0) {
break;
}
}
}
if (min_distance > best_distance) {
best_distance = min_distance;
best_timeslot = i;
}
}
_timesliced_proc[_num_timesliced_procs].proc = proc;
_timesliced_proc[_num_timesliced_procs].timeslot = best_timeslot;
_timesliced_proc[_num_timesliced_procs].freq_div = freq_div;
_num_timesliced_procs++;
return true;
}
void Scheduler::register_io_process(AP_HAL::MemberProc proc) void Scheduler::register_io_process(AP_HAL::MemberProc proc)
{ {
for (uint8_t i = 0; i < _num_io_procs; i++) { for (uint8_t i = 0; i < _num_io_procs; i++) {
@ -299,7 +243,9 @@ void Scheduler::_timer_task()
if (!_timer_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) { if (!_timer_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
printf("Failed to take timer semaphore in %s\n", __PRETTY_FUNCTION__); printf("Failed to take timer semaphore in %s\n", __PRETTY_FUNCTION__);
return;
} }
// now call the timer based drivers // now call the timer based drivers
for (i = 0; i < _num_timer_procs; i++) { for (i = 0; i < _num_timer_procs; i++) {
if (_timer_proc[i]) { if (_timer_proc[i]) {
@ -314,20 +260,6 @@ void Scheduler::_timer_task()
} }
#endif #endif
for (i = 0; i < _num_timesliced_procs; i++) {
if ((_timeslices_count + _timesliced_proc[i].timeslot)
% _timesliced_proc[i].freq_div == 0) {
_timesliced_proc[i].proc();
}
}
if (_max_freq_div != 0) {
_timeslices_count++;
if (_timeslices_count == _max_freq_div) {
_timeslices_count = 0;
}
}
_timer_semaphore.give(); _timer_semaphore.give();
// and the failsafe, if one is setup // and the failsafe, if one is setup

View File

@ -81,16 +81,6 @@ private:
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS]; AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS];
uint8_t _num_timer_procs; uint8_t _num_timer_procs;
volatile bool _in_timer_proc; volatile bool _in_timer_proc;
uint8_t _timeslices_count;
struct timesliced_proc {
AP_HAL::MemberProc proc;
uint8_t timeslot;
uint8_t freq_div;
};
timesliced_proc _timesliced_proc[LINUX_SCHEDULER_MAX_TIMESLICED_PROCS];
uint8_t _num_timesliced_procs;
uint8_t _max_freq_div;
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS]; AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS];
uint8_t _num_io_procs; uint8_t _num_io_procs;
@ -109,7 +99,6 @@ private:
void _run_io(); void _run_io();
void _run_uarts(); void _run_uarts();
bool _register_timesliced_proc(AP_HAL::MemberProc, uint8_t);
uint64_t _stopped_clock_usec; uint64_t _stopped_clock_usec;
uint64_t _last_stack_debug_msec; uint64_t _last_stack_debug_msec;