From bcf0733ea9195349be311d5c8d167e6216cc50c7 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 6 May 2024 18:53:09 +0100 Subject: [PATCH] AP_Periph: always limit rangefinder update rate to given max rate --- Tools/AP_Periph/rangefinder.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/AP_Periph/rangefinder.cpp b/Tools/AP_Periph/rangefinder.cpp index fc74399f322a71..981f4dca47c49e 100644 --- a/Tools/AP_Periph/rangefinder.cpp +++ b/Tools/AP_Periph/rangefinder.cpp @@ -39,6 +39,7 @@ void AP_Periph_FW::can_rangefinder_update(void) // limit to max rate return; } + last_rangefinder_update_ms = now; // update all rangefinder instances rangefinder.update(); @@ -114,7 +115,6 @@ void AP_Periph_FW::can_rangefinder_update(void) &buffer[0], total_size); - last_rangefinder_update_ms = now; } }