mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_Baro_MS5611: Support for timesliced timers
fallback if current scheduler doesn't support it
This commit is contained in:
parent
4acc121bd6
commit
d15097f3fc
@ -223,7 +223,8 @@ void AP_Baro_MS56XX::_init()
|
||||
hal.scheduler->resume_timer_procs();
|
||||
|
||||
if (_use_timer) {
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void));
|
||||
/* timer needs to be called every 10ms so set the freq_div to 10 */
|
||||
_timesliced = hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void), 10);
|
||||
}
|
||||
}
|
||||
|
||||
@ -310,7 +311,8 @@ bool AP_Baro_MS5637::_read_prom(uint16_t prom[8])
|
||||
void AP_Baro_MS56XX::_timer(void)
|
||||
{
|
||||
// Throttle read rate to 100hz maximum.
|
||||
if (AP_HAL::micros() - _last_timer < 10000) {
|
||||
if (!_timesliced &&
|
||||
AP_HAL::micros() - _last_timer < 10000) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -94,6 +94,7 @@ protected:
|
||||
volatile uint32_t _s_D1, _s_D2;
|
||||
uint8_t _state;
|
||||
uint32_t _last_timer;
|
||||
bool _timesliced;
|
||||
|
||||
bool _use_timer;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user