From 09947dace1a768f9f59e94268eead2b5099b7539 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 16 Dec 2011 19:45:49 +1100 Subject: [PATCH] ADC: only read channels that are actually being used on the APM2 we usually use none of the ADC channels, although we may use the airspeed sensor. This change means we detect which channels are being read, and only do the SPI transfers for those ones. That saves us about 100usec per timer interrupt (ie. about 10% of our CPU) --- libraries/AP_ADC/AP_ADC_ADS7844.cpp | 35 +++++++++++++++++++++++++++-- 1 file changed, 33 insertions(+), 2 deletions(-) diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.cpp b/libraries/AP_ADC/AP_ADC_ADS7844.cpp index 12affb8787..5dcce0303b 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS7844.cpp @@ -63,6 +63,11 @@ static volatile uint32_t _sum[8]; // how many values we've accumulated since last read static volatile uint16_t _count[8]; +// a mask of what channels are actually being read. If a channel has +// never been read, then don't bother gathering it. That saves us a +// lot of cycles in the timer call +static uint8_t enable_mask; + static uint32_t last_ch6_micros; // TCNT2 values for various interrupt rates, @@ -87,15 +92,35 @@ static inline unsigned char ADC_SPI_transfer(unsigned char data) void AP_ADC_ADS7844::read(void) { uint8_t ch; + unsigned char enable_cmd[9]; + uint8_t num_enabled = 0; + + if (enable_mask == 0) { + // no channels to read + return; + } + + for (ch = 0; ch < 8; ch++) { + if (enable_mask & (1<