mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
AnalogSource: convert analogRead() calls to the new API
this should give us much better analog values, plus save a bunch of CPU time
This commit is contained in:
parent
c8befe4536
commit
82ede937e7
@ -105,10 +105,13 @@ static void read_battery(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4)
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
||||||
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9;
|
static AP_AnalogSource_Arduino bat_pin(BATTERY_PIN_1);
|
||||||
|
battery_voltage1 = BATTERY_VOLTAGE(bat_pin.read_average());
|
||||||
|
}
|
||||||
if(g.battery_monitoring == 4) {
|
if(g.battery_monitoring == 4) {
|
||||||
current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin
|
static AP_AnalogSource_Arduino current_pin(CURRENT_PIN_1);
|
||||||
|
current_amps1 = CURRENT_AMPS(current_pin.read_average());
|
||||||
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours)
|
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -602,34 +602,10 @@ void flash_leds(bool on)
|
|||||||
#ifndef DESKTOP_BUILD
|
#ifndef DESKTOP_BUILD
|
||||||
/*
|
/*
|
||||||
* Read Vcc vs 1.1v internal reference
|
* 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)
|
uint16_t board_voltage(void)
|
||||||
{
|
{
|
||||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
static AP_AnalogSource_Arduino vcc(ANALOG_PIN_VCC);
|
||||||
|
return vcc.read_vcc();
|
||||||
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. We
|
|
||||||
// report 0V so it is clear in the logs that we don't know
|
|
||||||
// the value
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
uint32_t result = ADCL | ADCH<<8;
|
|
||||||
return 1126400UL / result; // Read and back-calculate Vcc in mV
|
|
||||||
}
|
|
||||||
// switch mux, settle time is needed. We don't want to delay
|
|
||||||
// waiting for the settle, so report 0 as a "don't know" value
|
|
||||||
ADMUX = mux;
|
|
||||||
return 0; // we don't know the current voltage
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -68,10 +68,13 @@ static void read_battery(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4)
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
||||||
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9;
|
static AP_AnalogSource_Arduino bat_pin(BATTERY_PIN_1);
|
||||||
|
battery_voltage1 = BATTERY_VOLTAGE(bat_pin.read_average());
|
||||||
|
}
|
||||||
if(g.battery_monitoring == 4) {
|
if(g.battery_monitoring == 4) {
|
||||||
current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin
|
static AP_AnalogSource_Arduino current_pin(CURRENT_PIN_1);
|
||||||
|
current_amps1 = CURRENT_AMPS(current_pin.read_average());
|
||||||
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -206,6 +206,9 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
timer_scheduler.init( &isr_registry );
|
timer_scheduler.init( &isr_registry );
|
||||||
|
|
||||||
|
// initialise the analog port reader
|
||||||
|
AP_AnalogSource_Arduino::init_timer(&timer_scheduler);
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
#if CONFIG_ADC == ENABLED
|
#if CONFIG_ADC == ENABLED
|
||||||
// begin filtering the ADC Gyros
|
// begin filtering the ADC Gyros
|
||||||
@ -657,34 +660,10 @@ void flash_leds(bool on)
|
|||||||
#ifndef DESKTOP_BUILD
|
#ifndef DESKTOP_BUILD
|
||||||
/*
|
/*
|
||||||
* Read Vcc vs 1.1v internal reference
|
* 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)
|
uint16_t board_voltage(void)
|
||||||
{
|
{
|
||||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
static AP_AnalogSource_Arduino vcc(ANALOG_PIN_VCC);
|
||||||
|
return vcc.read_vcc();
|
||||||
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. We
|
|
||||||
// report 0V so it is clear in the logs that we don't know
|
|
||||||
// the value
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
uint32_t result = ADCL | ADCH<<8;
|
|
||||||
return 1126400UL / result; // Read and back-calculate Vcc in mV
|
|
||||||
}
|
|
||||||
// switch mux, settle time is needed. We don't want to delay
|
|
||||||
// waiting for the settle, so report 0 as a "don't know" value
|
|
||||||
ADMUX = mux;
|
|
||||||
return 0; // we don't know the current voltage
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -66,10 +66,13 @@ static void read_battery(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4)
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
||||||
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9;
|
static AP_AnalogSource_Arduino bat_pin(BATTERY_PIN_1);
|
||||||
|
battery_voltage1 = BATTERY_VOLTAGE(bat_pin.read_average());
|
||||||
|
}
|
||||||
if(g.battery_monitoring == 4) {
|
if(g.battery_monitoring == 4) {
|
||||||
current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin
|
static AP_AnalogSource_Arduino current_pin(CURRENT_PIN_1);
|
||||||
|
current_amps1 = CURRENT_AMPS(current_pin.read_average());
|
||||||
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours)
|
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -118,6 +118,9 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
timer_scheduler.init( & isr_registry );
|
timer_scheduler.init( & isr_registry );
|
||||||
|
|
||||||
|
// initialise the analog port reader
|
||||||
|
AP_AnalogSource_Arduino::init_timer(&timer_scheduler);
|
||||||
|
|
||||||
//
|
//
|
||||||
// Check the EEPROM format version before loading any parameters from EEPROM.
|
// Check the EEPROM format version before loading any parameters from EEPROM.
|
||||||
//
|
//
|
||||||
@ -164,6 +167,9 @@ static void init_ardupilot()
|
|||||||
adc.Init(&timer_scheduler); // APM ADC library initialization
|
adc.Init(&timer_scheduler); // APM ADC library initialization
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// initialise the analog port reader
|
||||||
|
AP_AnalogSource_Arduino::init_timer(&timer_scheduler);
|
||||||
|
|
||||||
barometer.init(&timer_scheduler);
|
barometer.init(&timer_scheduler);
|
||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled==true) {
|
||||||
@ -574,34 +580,10 @@ void flash_leds(bool on)
|
|||||||
#ifndef DESKTOP_BUILD
|
#ifndef DESKTOP_BUILD
|
||||||
/*
|
/*
|
||||||
* Read Vcc vs 1.1v internal reference
|
* 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)
|
uint16_t board_voltage(void)
|
||||||
{
|
{
|
||||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
static AP_AnalogSource_Arduino vcc(ANALOG_PIN_VCC);
|
||||||
|
return vcc.read_vcc();
|
||||||
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. We
|
|
||||||
// report 0V so it is clear in the logs that we don't know
|
|
||||||
// the value
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
uint32_t result = ADCL | ADCH<<8;
|
|
||||||
return 1126400UL / result; // Read and back-calculate Vcc in mV
|
|
||||||
}
|
|
||||||
// switch mux, settle time is needed. We don't want to delay
|
|
||||||
// waiting for the settle, so report 0 as a "don't know" value
|
|
||||||
ADMUX = mux;
|
|
||||||
return 0; // we don't know the current voltage
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user