ADC: removed the ADC level accel smoothing
the quaternion code does a better job of handling this noise than this filter does
This commit is contained in:
parent
8ad6b5f4d1
commit
2b6fae6e16
@ -126,9 +126,7 @@ void AP_ADC_ADS7844::read(uint32_t tnow)
|
|||||||
|
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
AP_ADC_ADS7844::AP_ADC_ADS7844() :
|
AP_ADC_ADS7844::AP_ADC_ADS7844()
|
||||||
filter_result(false),
|
|
||||||
_filter_index_accel(0)
|
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -233,38 +231,6 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, float *result)
|
|||||||
result[i] = (sum[i] + count[i]) / (float)count[i];
|
result[i] = (sum[i] + count[i]) / (float)count[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
if(filter_result){
|
|
||||||
uint32_t _sum_accel;
|
|
||||||
|
|
||||||
// Accel filter
|
|
||||||
for (i = 0; i < 3; i++) {
|
|
||||||
// move most recent result into filter
|
|
||||||
_filter_accel[i][_filter_index_accel] = result[i+3];
|
|
||||||
|
|
||||||
// clear the sum
|
|
||||||
_sum_accel = 0;
|
|
||||||
|
|
||||||
// sum the filter
|
|
||||||
for (uint8_t n = 0; n < ADC_ACCEL_FILTER_SIZE; n++) {
|
|
||||||
_sum_accel += _filter_accel[i][n];
|
|
||||||
}
|
|
||||||
|
|
||||||
// filter does a moving average on last 8 reads, sums half with half of last filtered value
|
|
||||||
// save old result
|
|
||||||
_prev_accel[i] = result[i+3] = (_sum_accel >> 4) + (_prev_accel[i] >> 1); // divide by 16, divide by 2
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
// increment filter index
|
|
||||||
_filter_index_accel++;
|
|
||||||
|
|
||||||
// loop our filter
|
|
||||||
if(_filter_index_accel == ADC_ACCEL_FILTER_SIZE)
|
|
||||||
_filter_index_accel = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// return number of microseconds since last call
|
// return number of microseconds since last call
|
||||||
uint32_t us = micros();
|
uint32_t us = micros();
|
||||||
uint32_t ret = us - last_ch6_micros;
|
uint32_t ret = us - last_ch6_micros;
|
||||||
|
@ -33,13 +33,7 @@ class AP_ADC_ADS7844 : public AP_ADC
|
|||||||
// 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);
|
||||||
|
|
||||||
bool filter_result;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint16_t _filter_accel[3][ADC_ACCEL_FILTER_SIZE];
|
|
||||||
uint16_t _prev_gyro[3];
|
|
||||||
uint16_t _prev_accel[3];
|
|
||||||
uint8_t _filter_index_accel;
|
|
||||||
static void read(uint32_t);
|
static void read(uint32_t);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user