mirror of https://github.com/ArduPilot/ardupilot
ADC: on channel overflow we should not zero last_ch6_micros
this happens every 64 seconds because of unused channels on the ADC. Zeroing this creates a bad delta_t value for the DCM code.
This commit is contained in:
parent
f8ed9f0e8d
commit
3fbb5a2d6c
|
@ -116,7 +116,6 @@ void AP_ADC_ADS7844::read(uint32_t tnow)
|
||||||
// reader below could get a division by zero
|
// reader below could get a division by zero
|
||||||
_sum[ch] = 0;
|
_sum[ch] = 0;
|
||||||
_count[ch] = 1;
|
_count[ch] = 1;
|
||||||
last_ch6_micros = tnow;
|
|
||||||
}
|
}
|
||||||
_sum[ch] += (v >> 3);
|
_sum[ch] += (v >> 3);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue