AP_HAL: always choose high for dshot prescaler calculation

This commit is contained in:
Andy Piper 2022-03-07 20:01:53 +00:00 committed by Andrew Tridgell
parent e0e60c8654
commit 85d73eeb5c
2 changed files with 17 additions and 9 deletions

View File

@ -86,15 +86,23 @@ uint32_t AP_HAL::RCOutput::calculate_bitrate_prescaler(uint32_t timer_clock, uin
}
}
// find the closest value
const uint32_t freq = timer_clock / prescaler;
const float delta = fabsf(float(freq) - target_frequency);
if (freq > target_frequency
&& delta > fabsf(float(timer_clock / (prescaler+1)) - target_frequency)) {
prescaler++;
} else if (freq < target_frequency
&& delta > fabsf(float(timer_clock / (prescaler-1)) - target_frequency)) {
prescaler--;
// if using dshot then always pick the high value. choosing low seems to not agree with some
// ESCs despite the fact that BLHeli32 is supposed not to care what the bitrate is
if (is_dshot) {
if (freq < target_frequency) {
prescaler--;
}
} else {
// find the closest value
const float delta = fabsf(float(freq) - target_frequency);
if (freq > target_frequency
&& delta > fabsf(float(timer_clock / (prescaler+1)) - target_frequency)) {
prescaler++;
} else if (freq < target_frequency
&& delta > fabsf(float(timer_clock / (prescaler-1)) - target_frequency)) {
prescaler--;
}
}
return prescaler;

View File

@ -11,7 +11,7 @@ protected:
const uint32_t prescaler = AP_HAL::RCOutput::calculate_bitrate_prescaler(clock, target_rate, is_dshot);
// we would like at most a 1% discrepancy in target versus actual
const float rate_delta = fabsf(float(clock / prescaler) - target_rate) / target_rate;
EXPECT_TRUE(rate_delta < 0.13f);
EXPECT_TRUE(rate_delta < 0.20f);
}
};