AP_RPM: make dt_avg a float value by using float division

Previously, it was using interger division and thus lost the fractional part
This commit is contained in:
Pierre Kancir 2021-08-13 09:57:10 +02:00 committed by Randy Mackay
parent 7ecb580519
commit 5a9542be81

View File

@ -76,11 +76,10 @@ void AP_RPM_Pin::update(void)
}
if (irq_state[state.instance].dt_count > 0) {
float dt_avg;
// disable interrupts to prevent race with irq_handler
void *irqstate = hal.scheduler->disable_interrupts_save();
dt_avg = irq_state[state.instance].dt_sum / irq_state[state.instance].dt_count;
const float dt_avg = static_cast<float>(irq_state[state.instance].dt_sum) / irq_state[state.instance].dt_count;
irq_state[state.instance].dt_count = 0;
irq_state[state.instance].dt_sum = 0;
hal.scheduler->restore_interrupts(irqstate);