ADC: change adc.Ch() to return a float

this gives us a bit more precision in airspeed measurement, and costs
us virtually nothing as we are converting to float immediately after
getting the value
This commit is contained in:
Andrew Tridgell 2011-12-10 21:43:57 +11:00
parent 43a53aa303
commit 47da2ec992
5 changed files with 6 additions and 6 deletions

View File

@ -27,7 +27,7 @@ class AP_ADC
virtual void Init(AP_PeriodicProcess * scheduler = NULL) = 0; virtual void Init(AP_PeriodicProcess * scheduler = NULL) = 0;
/* read one channel value */ /* read one channel value */
virtual uint16_t Ch(uint8_t ch_num) = 0; virtual float Ch(uint8_t ch_num) = 0;
/* read 6 channels values as a set, used by IMU for 3 gyros /* read 6 channels values as a set, used by IMU for 3 gyros
and 3 accelerometeres. and 3 accelerometeres.

View File

@ -162,7 +162,7 @@ void AP_ADC_ADS7844::Init( AP_PeriodicProcess * scheduler )
} }
// Read one channel value // Read one channel value
uint16_t AP_ADC_ADS7844::Ch(uint8_t ch_num) float AP_ADC_ADS7844::Ch(uint8_t ch_num)
{ {
uint16_t count; uint16_t count;
uint32_t sum; uint32_t sum;
@ -178,7 +178,7 @@ uint16_t AP_ADC_ADS7844::Ch(uint8_t ch_num)
_sum[ch_num] = 0; _sum[ch_num] = 0;
sei(); sei();
return sum/count; return ((float)sum)/count;
} }
// Read 6 channel values // Read 6 channel values

View File

@ -24,7 +24,7 @@ class AP_ADC_ADS7844 : public AP_ADC
void Init( AP_PeriodicProcess * scheduler ); void Init( AP_PeriodicProcess * scheduler );
// Read 1 sensor value // Read 1 sensor value
uint16_t Ch(unsigned char ch_num); float Ch(unsigned char ch_num);
// 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);

View File

@ -44,7 +44,7 @@ void AP_ADC_HIL::Init( AP_PeriodicProcess * scheduler )
} }
// Read one channel value // Read one channel value
uint16_t AP_ADC_HIL::Ch(unsigned char ch_num) float AP_ADC_HIL::Ch(unsigned char ch_num)
{ {
return adcValue[ch_num]; return adcValue[ch_num];
} }

View File

@ -32,7 +32,7 @@ class AP_ADC_HIL : public AP_ADC
/// ///
// Read the sensor, part of public AP_ADC interface // Read the sensor, part of public AP_ADC interface
uint16_t Ch(unsigned char ch_num); float Ch(unsigned char ch_num);
/// ///
// Read 6 sensors at once // Read 6 sensors at once