mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Fix calls to AP_HAL::Scheduler::register_timer_process
This commit is contained in:
parent
bae7e4b88e
commit
668caa4a2e
@ -163,7 +163,7 @@ void AP_ADC_ADS7844::Init()
|
|||||||
_ch6_last_sample_time_micros = hal.scheduler->micros();
|
_ch6_last_sample_time_micros = hal.scheduler->micros();
|
||||||
|
|
||||||
hal.scheduler->resume_timer_procs();
|
hal.scheduler->resume_timer_procs();
|
||||||
hal.scheduler->register_timer_process( AP_ADC_ADS7844::read, 1, 0);
|
hal.scheduler->register_timer_process( AP_ADC_ADS7844::read );
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -144,7 +144,7 @@ bool AP_Baro_MS5611::init()
|
|||||||
_d1_count = 0;
|
_d1_count = 0;
|
||||||
_d2_count = 0;
|
_d2_count = 0;
|
||||||
|
|
||||||
hal.scheduler->register_timer_process( AP_Baro_MS5611::_update, 1, 0);
|
hal.scheduler->register_timer_process( AP_Baro_MS5611::_update );
|
||||||
hal.scheduler->resume_timer_procs();
|
hal.scheduler->resume_timer_procs();
|
||||||
|
|
||||||
// wait for at least one value to be read
|
// wait for at least one value to be read
|
||||||
|
Loading…
Reference in New Issue
Block a user