From 5a9542be8159f2f732e1930c55f99c0960b3cdc6 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Fri, 13 Aug 2021 09:57:10 +0200 Subject: [PATCH] AP_RPM: make dt_avg a float value by using float division Previously, it was using interger division and thus lost the fractional part --- libraries/AP_RPM/RPM_Pin.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_RPM/RPM_Pin.cpp b/libraries/AP_RPM/RPM_Pin.cpp index 83a0039a71..aedf81570a 100644 --- a/libraries/AP_RPM/RPM_Pin.cpp +++ b/libraries/AP_RPM/RPM_Pin.cpp @@ -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(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);