ADC: use floats for ADC averaging

this costs almost nothing and improved accel/gyro calibration
This commit is contained in:
Andrew Tridgell 2012-03-07 15:14:29 +11:00
parent d17a7e81e3
commit 404a4e4896
5 changed files with 6 additions and 6 deletions

View File

@ -38,7 +38,7 @@ class AP_ADC
The function returns the amount of time (in microseconds) The function returns the amount of time (in microseconds)
since the last call to Ch6(). since the last call to Ch6().
*/ */
virtual uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result) = 0; virtual uint32_t Ch6(const uint8_t *channel_numbers, float *result) = 0;
// check if Ch6() can return new data // check if Ch6() can return new data
virtual bool new_data_available(const uint8_t *channel_numbers) = 0; virtual bool new_data_available(const uint8_t *channel_numbers) = 0;

View File

@ -204,7 +204,7 @@ bool AP_ADC_ADS7844::new_data_available(const uint8_t *channel_numbers)
// equal. This will only be true if we always consistently access a // equal. This will only be true if we always consistently access a
// sensor by either Ch6() or Ch() and never mix them. If you mix them // sensor by either Ch6() or Ch() and never mix them. If you mix them
// then you will get very strange results // then you will get very strange results
uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result) uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, float *result)
{ {
uint16_t count[6]; uint16_t count[6];
uint32_t sum[6]; uint32_t sum[6];
@ -230,7 +230,7 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result)
// division. That costs us 36 bytes of stack, but I think its // division. That costs us 36 bytes of stack, but I think its
// worth it. // worth it.
for (i = 0; i < 6; i++) { for (i = 0; i < 6; i++) {
result[i] = (sum[i] + (count[i]/2)) / count[i]; result[i] = (sum[i] + count[i]) / (float)count[i];
} }

View File

@ -28,7 +28,7 @@ class AP_ADC_ADS7844 : public AP_ADC
float 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, float *result);
// check if Ch6 would block // check if Ch6 would block
bool new_data_available(const uint8_t *channel_numbers); bool new_data_available(const uint8_t *channel_numbers);

View File

@ -54,7 +54,7 @@ float AP_ADC_HIL::Ch(unsigned char ch_num)
} }
// Read 6 channel values // Read 6 channel values
uint32_t AP_ADC_HIL::Ch6(const uint8_t *channel_numbers, uint16_t *result) uint32_t AP_ADC_HIL::Ch6(const uint8_t *channel_numbers, float *result)
{ {
for (uint8_t i=0; i<6; i++) { for (uint8_t i=0; i<6; i++) {
result[i] = Ch(channel_numbers[i]); result[i] = Ch(channel_numbers[i]);

View File

@ -36,7 +36,7 @@ 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, float *result);
// see if Ch6 would block // see if Ch6 would block
bool new_data_available(const uint8_t *channel_numbers); bool new_data_available(const uint8_t *channel_numbers);