mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
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:
parent
7ecb580519
commit
5a9542be81
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user