AP_ADC: added new_data_available() interface

returns true if more samples are available
This commit is contained in:
Andrew Tridgell 2012-03-03 18:31:09 +11:00
parent 4a277f9871
commit 61d649e7ac
5 changed files with 30 additions and 0 deletions

View File

@ -40,6 +40,9 @@ class AP_ADC
*/ */
virtual uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result) = 0; virtual uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result) = 0;
// check if Ch6() can return new data
virtual bool new_data_available(const uint8_t *channel_numbers) = 0;
private: private:
}; };

View File

@ -185,6 +185,20 @@ float AP_ADC_ADS7844::Ch(uint8_t ch_num)
return ((float)sum)/count; return ((float)sum)/count;
} }
// see if Ch6() can return new data
bool AP_ADC_ADS7844::new_data_available(const uint8_t *channel_numbers)
{
uint8_t i;
for (i=0; i<6; i++) {
if (_count[channel_numbers[i]] == 0) {
return false;
}
}
return true;
}
// Read 6 channel values // Read 6 channel values
// this assumes that the counts for all of the 6 channels are // this assumes that the counts for all of the 6 channels are
// equal. This will only be true if we always consistently access a // equal. This will only be true if we always consistently access a

View File

@ -29,6 +29,10 @@ class AP_ADC_ADS7844 : public AP_ADC
// Read 6 sensors at once // Read 6 sensors at once
uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result); uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result);
// check if Ch6 would block
bool new_data_available(const uint8_t *channel_numbers);
bool filter_result; bool filter_result;
private: private:

View File

@ -82,3 +82,9 @@ void AP_ADC_HIL::setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp,
// differential pressure // differential pressure
setPressure(diffPress); setPressure(diffPress);
} }
// see if new data is available
bool AP_ADC_HIL::new_data_available(const uint8_t *channel_numbers)
{
return true;
}

View File

@ -38,6 +38,9 @@ class AP_ADC_HIL : public AP_ADC
// Read 6 sensors at once // Read 6 sensors at once
uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result); uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result);
// see if Ch6 would block
bool new_data_available(const uint8_t *channel_numbers);
/// ///
// Set the adc raw values given the current rotations rates, // Set the adc raw values given the current rotations rates,
// temps, accels, and pressures // temps, accels, and pressures