mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AnalogSource: prevent a division by zero on zero ADC data
This commit is contained in:
parent
f6d7d1bc59
commit
d755fedc26
@ -94,7 +94,11 @@ uint16_t AP_AnalogSource_Arduino::read_raw(void)
|
||||
// scaled read for board Vcc
|
||||
uint16_t AP_AnalogSource_Arduino::read_vcc(void)
|
||||
{
|
||||
return 1126400UL / read_raw();
|
||||
uint16_t v = read_raw();
|
||||
if (v == 0) {
|
||||
return 0;
|
||||
}
|
||||
return 1126400UL / v;
|
||||
}
|
||||
|
||||
// read the average 16 bit value since the last
|
||||
|
Loading…
Reference in New Issue
Block a user