HAL_AVR: updates for AP_HAL::MemberProc

This commit is contained in:
Andrew Tridgell 2013-09-30 17:00:38 +10:00
parent f2de4bb7b0
commit 6d58f5e188
3 changed files with 14 additions and 17 deletions

View File

@ -23,7 +23,7 @@ AVRAnalogIn::AVRAnalogIn() :
void AVRAnalogIn::init(void* machtnichts)
{
/* Register AVRAnalogIn::_timer_event with the scheduler. */
hal.scheduler->register_timer_process(reinterpret_cast<AP_HAL::TimedProc>(&AVRAnalogIn::_timer_event), this);
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AVRAnalogIn::_timer_event));
/* Register each private channel with AVRAnalogIn. */
_register_channel(&_vcc);
}

View File

@ -20,12 +20,11 @@ extern const AP_HAL::HAL& hal;
/* Static AVRScheduler variables: */
AVRTimer AVRScheduler::_timer;
AP_HAL::TimedProc AVRScheduler::_failsafe = NULL;
AP_HAL::Proc AVRScheduler::_failsafe = NULL;
volatile bool AVRScheduler::_timer_suspended = false;
volatile bool AVRScheduler::_timer_event_missed = false;
volatile bool AVRScheduler::_in_timer_proc = false;
AP_HAL::TimedProc AVRScheduler::_timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
void *AVRScheduler::_timer_arg[AVR_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
AP_HAL::MemberProc AVRScheduler::_timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS] = {NULL};
uint8_t AVRScheduler::_num_timer_procs = 0;
@ -89,7 +88,7 @@ void AVRScheduler::register_delay_callback(AP_HAL::Proc proc,
_min_delay_cb_ms = min_time_ms;
}
void AVRScheduler::register_timer_process(AP_HAL::TimedProc proc, void *arg)
void AVRScheduler::register_timer_process(AP_HAL::MemberProc proc)
{
for (int i = 0; i < _num_timer_procs; i++) {
if (_timer_proc[i] == proc) {
@ -102,7 +101,6 @@ void AVRScheduler::register_timer_process(AP_HAL::TimedProc proc, void *arg)
* because that memory won't be used until _num_timer_procs is
* incremented. */
_timer_proc[_num_timer_procs] = proc;
_timer_arg[_num_timer_procs] = arg;
/* _num_timer_procs is used from interrupt, and multiple bytes long. */
uint8_t sreg = SREG;
cli();
@ -112,12 +110,12 @@ void AVRScheduler::register_timer_process(AP_HAL::TimedProc proc, void *arg)
}
void AVRScheduler::register_io_process(AP_HAL::TimedProc proc, void *arg)
void AVRScheduler::register_io_process(AP_HAL::MemberProc proc)
{
// IO processes not supported on AVR
}
void AVRScheduler::register_timer_failsafe(AP_HAL::TimedProc failsafe, uint32_t period_us) {
void AVRScheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us) {
/* XXX Assert period_us == 1000 */
_failsafe = failsafe;
}
@ -165,7 +163,7 @@ void AVRScheduler::_run_timer_procs(bool called_from_isr) {
// block. If it does then we will recurse and die when
// we run out of stack
if (_failsafe != NULL) {
_failsafe(NULL);
_failsafe();
}
return;
}
@ -176,7 +174,7 @@ void AVRScheduler::_run_timer_procs(bool called_from_isr) {
// now call the timer based drivers
for (int i = 0; i < _num_timer_procs; i++) {
if (_timer_proc[i] != NULL) {
_timer_proc[i](_timer_arg[i]);
_timer_proc[i]();
}
}
} else if (called_from_isr) {
@ -185,7 +183,7 @@ void AVRScheduler::_run_timer_procs(bool called_from_isr) {
// and the failsafe, if one is setup
if (_failsafe != NULL) {
_failsafe(NULL);
_failsafe();
}
_in_timer_proc = false;

View File

@ -31,14 +31,14 @@ public:
void delay_microseconds(uint16_t us);
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
void register_timer_process(AP_HAL::TimedProc, void *);
void register_io_process(AP_HAL::TimedProc, void *);
void register_timer_process(AP_HAL::MemberProc);
void register_io_process(AP_HAL::MemberProc);
void suspend_timer_procs();
void resume_timer_procs();
bool in_timerprocess();
void register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
bool system_initializing();
void system_initialized();
@ -60,12 +60,11 @@ private:
static void _timer_isr_event();
static void _run_timer_procs(bool called_from_isr);
static AP_HAL::TimedProc _failsafe;
static AP_HAL::Proc _failsafe;
static volatile bool _timer_suspended;
static volatile bool _timer_event_missed;
static AP_HAL::TimedProc _timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS];
static void *_timer_arg[AVR_SCHEDULER_MAX_TIMER_PROCS];
static AP_HAL::MemberProc _timer_proc[AVR_SCHEDULER_MAX_TIMER_PROCS];
static uint8_t _num_timer_procs;
};