Copter: ensure decimated rates are never 0 in rate thread

This commit is contained in:
Andy Piper 2024-10-05 18:26:22 +01:00 committed by Andrew Tridgell
parent 6db09c9fdd
commit c823374986
1 changed files with 1 additions and 1 deletions

View File

@ -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)