|
|
|
@ -60,6 +60,26 @@ float ADCSource::voltage_average(void)
@@ -60,6 +60,26 @@ float ADCSource::voltage_average(void)
|
|
|
|
|
return v * vcc_mV * 9.765625e-7; // 9.765625e-7 = 1.0/(1024*1000)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
return voltage from 0.0 to 5.0V, scaled to Vcc |
|
|
|
|
*/ |
|
|
|
|
float ADCSource::voltage_latest(void) |
|
|
|
|
{ |
|
|
|
|
if (_pin == ANALOG_INPUT_BOARD_VCC) { |
|
|
|
|
return read_latest() * 0.001f; |
|
|
|
|
} |
|
|
|
|
float vcc_mV = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC)->read_average(); |
|
|
|
|
float v = read_latest(); |
|
|
|
|
// constrain Vcc reading so that a bad Vcc doesn't throw off
|
|
|
|
|
// the reading of other sources too badly
|
|
|
|
|
if (vcc_mV < 4000) { |
|
|
|
|
vcc_mV = 4000; |
|
|
|
|
} else if (vcc_mV > 6000) { |
|
|
|
|
vcc_mV = 6000; |
|
|
|
|
} |
|
|
|
|
return v * vcc_mV * 9.765625e-7; // 9.765625e-7 = 1.0/(1024*1000)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
return voltage from 0.0 to 5.0V, assuming a ratiometric sensor. This |
|
|
|
|
means the result is really a pseudo-voltage, that assumes the supply |
|
|
|
|