ADC: remove a very small (0.2 degrees/s) bias in the ADC code

small bias from integer rounding
This commit is contained in:
Andrew Tridgell 2011-11-28 16:00:28 +11:00
parent 2cabb11307
commit e491168273
1 changed files with 1 additions and 1 deletions

View File

@ -212,7 +212,7 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result)
// division. That costs us 36 bytes of stack, but I think its
// worth it.
for (i = 0; i < 6; i++) {
result[i] = sum[i] / count[i];
result[i] = (sum[i] + (count[i]/2)) / count[i];
}