mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_PX4: updates for AP_HAL::MemberProc
This commit is contained in:
parent
f2ebb2ca87
commit
942ae70651
@ -128,7 +128,7 @@ void PX4Scheduler::register_delay_callback(AP_HAL::Proc proc,
|
||||
_min_delay_cb_ms = min_time_ms;
|
||||
}
|
||||
|
||||
void PX4Scheduler::register_timer_process(AP_HAL::TimedProc proc, void *arg)
|
||||
void PX4Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
||||
if (_timer_proc[i] == proc) {
|
||||
@ -138,14 +138,13 @@ void PX4Scheduler::register_timer_process(AP_HAL::TimedProc proc, void *arg)
|
||||
|
||||
if (_num_timer_procs < PX4_SCHEDULER_MAX_TIMER_PROCS) {
|
||||
_timer_proc[_num_timer_procs] = proc;
|
||||
_timer_arg[_num_timer_procs] = arg;
|
||||
_num_timer_procs++;
|
||||
} else {
|
||||
hal.console->printf("Out of timer processes\n");
|
||||
}
|
||||
}
|
||||
|
||||
void PX4Scheduler::register_io_process(AP_HAL::TimedProc proc, void *arg)
|
||||
void PX4Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
||||
if (_io_proc[i] == proc) {
|
||||
@ -155,14 +154,13 @@ void PX4Scheduler::register_io_process(AP_HAL::TimedProc proc, void *arg)
|
||||
|
||||
if (_num_io_procs < PX4_SCHEDULER_MAX_TIMER_PROCS) {
|
||||
_io_proc[_num_io_procs] = proc;
|
||||
_io_arg[_num_io_procs] = arg;
|
||||
_num_io_procs++;
|
||||
} else {
|
||||
hal.console->printf("Out of IO processes\n");
|
||||
}
|
||||
}
|
||||
|
||||
void PX4Scheduler::register_timer_failsafe(AP_HAL::TimedProc failsafe, uint32_t period_us)
|
||||
void PX4Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
||||
{
|
||||
_failsafe = failsafe;
|
||||
}
|
||||
@ -197,7 +195,7 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
// 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_timer_thread) {
|
||||
@ -206,7 +204,7 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
_failsafe(NULL);
|
||||
_failsafe();
|
||||
}
|
||||
|
||||
// process analog input
|
||||
@ -245,7 +243,7 @@ void PX4Scheduler::_run_io(void)
|
||||
// now call the IO based drivers
|
||||
for (int i = 0; i < _num_io_procs; i++) {
|
||||
if (_io_proc[i] != NULL) {
|
||||
_io_proc[i](_io_arg[i]);
|
||||
_io_proc[i]();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -31,9 +31,9 @@ public:
|
||||
uint32_t micros();
|
||||
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_failsafe(AP_HAL::TimedProc, uint32_t period_us);
|
||||
void register_timer_process(AP_HAL::MemberProc);
|
||||
void register_io_process(AP_HAL::MemberProc);
|
||||
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
|
||||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
void reboot(bool hold_in_bootloader);
|
||||
@ -47,19 +47,17 @@ private:
|
||||
bool _initialized;
|
||||
AP_HAL::Proc _delay_cb;
|
||||
uint16_t _min_delay_cb_ms;
|
||||
AP_HAL::TimedProc _failsafe;
|
||||
AP_HAL::Proc _failsafe;
|
||||
volatile bool _timer_pending;
|
||||
uint64_t _sketch_start_time;
|
||||
|
||||
volatile bool _timer_suspended;
|
||||
|
||||
AP_HAL::TimedProc _timer_proc[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
||||
void * _timer_arg[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
||||
AP_HAL::MemberProc _timer_proc[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
||||
uint8_t _num_timer_procs;
|
||||
volatile bool _in_timer_proc;
|
||||
|
||||
AP_HAL::TimedProc _io_proc[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
||||
void * _io_arg[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
||||
AP_HAL::MemberProc _io_proc[PX4_SCHEDULER_MAX_TIMER_PROCS];
|
||||
uint8_t _num_io_procs;
|
||||
volatile bool _in_io_proc;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user