From 5a3645d36a93d2d3321ab1869aecc4b4bc81dbe1 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Thu, 30 Aug 2012 16:50:03 +0900 Subject: [PATCH] AP_ADC: added num_samples_available to allow main loop to be synced with arrival of new sensor data for Oilpan. --- libraries/AP_ADC/AP_ADC.h | 2 ++ libraries/AP_ADC/AP_ADC_ADS7844.cpp | 15 +++++++++++++++ libraries/AP_ADC/AP_ADC_ADS7844.h | 3 +++ libraries/AP_ADC/AP_ADC_HIL.cpp | 6 ++++++ libraries/AP_ADC/AP_ADC_HIL.h | 3 +++ 5 files changed, 29 insertions(+) diff --git a/libraries/AP_ADC/AP_ADC.h b/libraries/AP_ADC/AP_ADC.h index 0a257e3263..7a09ebf557 100644 --- a/libraries/AP_ADC/AP_ADC.h +++ b/libraries/AP_ADC/AP_ADC.h @@ -44,6 +44,8 @@ public: // check if Ch6() can return new data virtual bool new_data_available(const uint8_t *channel_numbers) = 0; + virtual uint16_t num_samples_available(const uint8_t *channel_numbers) = 0; + private: }; diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.cpp b/libraries/AP_ADC/AP_ADC_ADS7844.cpp index 01c13e7a9d..dfb8780798 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS7844.cpp @@ -246,3 +246,18 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, float *result) // return number of microseconds since last call return ret; } + +/// Get minimum number of samples read from the sensors +uint16_t AP_ADC_ADS7844::num_samples_available(const uint8_t *channel_numbers) +{ + // get count of first channel as a base + uint16_t min_count = _count[channel_numbers[0]]; + + // reduce to minimum count of all other channels + for (uint8_t i=1; i<6; i++) { + if (_count[channel_numbers[i]] < min_count) { + min_count = _count[channel_numbers[i]]; + } + } + return min_count; +} diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.h b/libraries/AP_ADC/AP_ADC_ADS7844.h index 66098a7994..71452161f4 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.h +++ b/libraries/AP_ADC/AP_ADC_ADS7844.h @@ -33,6 +33,9 @@ public: // check if Ch6 would block bool new_data_available(const uint8_t *channel_numbers); + // Get minimum number of samples read from the sensors + uint16_t num_samples_available(const uint8_t *channel_numbers); + private: static void read(uint32_t); diff --git a/libraries/AP_ADC/AP_ADC_HIL.cpp b/libraries/AP_ADC/AP_ADC_HIL.cpp index 2cf0811157..5ea1efaba1 100644 --- a/libraries/AP_ADC/AP_ADC_HIL.cpp +++ b/libraries/AP_ADC/AP_ADC_HIL.cpp @@ -88,3 +88,9 @@ bool AP_ADC_HIL::new_data_available(const uint8_t *channel_numbers) { return true; } + +// Get minimum number of samples read from the sensors +uint16_t AP_ADC_HIL::num_samples_available(const uint8_t *channel_numbers) +{ + return 1; +} \ No newline at end of file diff --git a/libraries/AP_ADC/AP_ADC_HIL.h b/libraries/AP_ADC/AP_ADC_HIL.h index 22502359c9..b44147e891 100644 --- a/libraries/AP_ADC/AP_ADC_HIL.h +++ b/libraries/AP_ADC/AP_ADC_HIL.h @@ -41,6 +41,9 @@ public: // see if Ch6 would block bool new_data_available(const uint8_t *channel_numbers); + // Get minimum number of samples read from the sensors + uint16_t num_samples_available(const uint8_t *channel_numbers); + /// // Set the adc raw values given the current rotations rates, // temps, accels, and pressures