From c823374986f9b93f6c3c2935a732d10550a1ceaa Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 5 Oct 2024 18:26:22 +0100 Subject: [PATCH] Copter: ensure decimated rates are never 0 in rate thread --- ArduCopter/rate_thread.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/rate_thread.cpp b/ArduCopter/rate_thread.cpp index 115c589729..ef8b624c54 100644 --- a/ArduCopter/rate_thread.cpp +++ b/ArduCopter/rate_thread.cpp @@ -152,7 +152,7 @@ uint8_t Copter::calc_gyro_decimation(uint8_t gyro_decimation, uint16_t rate_hz) { - return uint8_t(DIV_ROUND_INT(ins.get_raw_gyro_rate_hz() / gyro_decimation, rate_hz)); + return MAX(uint8_t(DIV_ROUND_INT(ins.get_raw_gyro_rate_hz() / gyro_decimation, rate_hz)), 1U); } static inline bool run_decimated_callback(uint8_t decimation_rate, uint8_t& decimation_count)