AP_ADC_AnalogSource: fixed reference scaling for APM1 Ch6 ADC
it is not referenced to Vcc
This commit is contained in:
parent
2fc922a251
commit
bf1944a36d
@ -22,10 +22,10 @@ float AP_ADC_AnalogSource::read_average() {
|
|||||||
*/
|
*/
|
||||||
float AP_ADC_AnalogSource::voltage_average()
|
float AP_ADC_AnalogSource::voltage_average()
|
||||||
{
|
{
|
||||||
float vcc_mV = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC)->read_average();
|
|
||||||
float fullscale = _adc->Ch(_ch);
|
float fullscale = _adc->Ch(_ch);
|
||||||
// note that the Ch6 ADC on APM1 has a 3.3V range
|
// note that the Ch6 ADC on APM1 has a 3.3V range, and is against
|
||||||
return fullscale * vcc_mV * (3.3/5.0) * 2.44140625e-7f; // 1.0/(4096*1000)
|
// an internal reference, not the 5V power supply
|
||||||
|
return fullscale * 3.3 * 2.44140625e-4f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user