mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
ADC: minor fix to the ADC Ch6() code
we don't need to add count any more, as floating point maths doesn't need to round up
This commit is contained in:
parent
989304fb47
commit
9b95d2060a
@ -228,7 +228,7 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, float *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]) / (float)count[i];
|
||||
result[i] = sum[i] / (float)count[i];
|
||||
}
|
||||
|
||||
// return number of microseconds since last call
|
||||
|
Loading…
Reference in New Issue
Block a user