mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM: added board_voltage() function
This commit is contained in:
parent
1e8d98cdda
commit
b20084af7d
@ -565,3 +565,36 @@ void flash_leds(bool on)
|
||||
digitalWrite(A_LED_PIN, on?LED_OFF:LED_ON);
|
||||
digitalWrite(C_LED_PIN, on?LED_ON:LED_OFF);
|
||||
}
|
||||
|
||||
#ifndef DESKTOP_BUILD
|
||||
/*
|
||||
* Read Vcc vs 1.1v internal reference
|
||||
*
|
||||
* This call takes about 150us total. ADC conversion is 13 cycles of
|
||||
* 125khz default changes the mux if it isn't set, and return last
|
||||
* reading (allows necessary settle time) otherwise trigger the
|
||||
* conversion
|
||||
*/
|
||||
uint16_t board_voltage(void)
|
||||
{
|
||||
static uint16_t vcc = 5000;
|
||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
||||
|
||||
if (ADMUX == mux) {
|
||||
ADCSRA |= _BV(ADSC); // Convert
|
||||
uint16_t counter=4000; // normally takes about 1700 loops
|
||||
while (bit_is_set(ADCSRA, ADSC) && counter) // Wait
|
||||
counter--;
|
||||
if (counter == 0) {
|
||||
// we don't actually expect this timeout to happen,
|
||||
// but we don't want any more code that could hang
|
||||
return vcc;
|
||||
}
|
||||
uint32_t result = ADCL | ADCH<<8;
|
||||
vcc = 1126400L / result; // Read and back-calculate Vcc in mV
|
||||
} else {
|
||||
ADMUX = mux; // switch mux, settle time is needed
|
||||
}
|
||||
return vcc; // in mV
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user