Filter - added AverageFilter, removed SumFilter

added FilterWithBuffer to allow removal of malloc/free without losing ability to pass around filter objects
This commit is contained in:
rmackay9 2012-02-28 21:01:11 +09:00
parent 078268528e
commit d17a015df1
6 changed files with 215 additions and 182 deletions

View File

@ -16,14 +16,16 @@
#include <inttypes.h>
#include <Filter.h>
#include <FilterWithBuffer.h>
// 1st parameter <T> is the type of data being filtered.
// 2nd parameter <U> is a larger data type used during summation to prevent overflows
template <class T, class U>
class AverageFilter : public Filter<T>
template <class T, class U, uint8_t FILTER_SIZE>
class AverageFilter : public FilterWithBuffer<T,FILTER_SIZE>
{
public:
AverageFilter(uint8_t requested_size) : Filter<T>(requested_size) {};
// constructor
AverageFilter() : FilterWithBuffer<T,FILTER_SIZE>(), _num_samples(0) {};
// apply - Add a new raw value to the filter, retrieve the filtered result
virtual T apply(T sample);
@ -32,51 +34,68 @@ class AverageFilter : public Filter<T>
virtual void reset();
private:
uint8_t _num_samples;
uint8_t _num_samples; // the number of samples in the filter, maxes out at size of the filter
};
// Typedef for convenience (1st argument is the data size, 2nd argument is a datasize that's bigger to handle overflows)
typedef AverageFilter<int8_t, int16_t> AverageFilterInt8;
typedef AverageFilter<uint8_t, uint16_t> AverageFilterUInt8;
typedef AverageFilter<int16_t, int32_t> AverageFilterInt16;
typedef AverageFilter<uint16_t, uint32_t> AverageFilterUInt16;
typedef AverageFilter<int32_t, float> AverageFilterInt32;
typedef AverageFilter<uint32_t, float> AverageFilterUInt32;
// Typedef for convenience (1st argument is the data type, 2nd is a larger datatype to handle overflows, 3rd is buffer size)
typedef AverageFilter<int8_t,int16_t,2> AverageFilterInt8_Size2;
typedef AverageFilter<int8_t,int16_t,3> AverageFilterInt8_Size3;
typedef AverageFilter<int8_t,int16_t,4> AverageFilterInt8_Size4;
typedef AverageFilter<int8_t,int16_t,5> AverageFilterInt8_Size5;
typedef AverageFilter<uint8_t,uint16_t,2> AverageFilterUInt8_Size2;
typedef AverageFilter<uint8_t,uint16_t,3> AverageFilterUInt8_Size3;
typedef AverageFilter<uint8_t,uint16_t,4> AverageFilterUInt8_Size4;
typedef AverageFilter<uint8_t,uint16_t,5> AverageFilterUInt8_Size5;
typedef AverageFilter<int16_t,int32_t,2> AverageFilterInt16_Size2;
typedef AverageFilter<int16_t,int32_t,3> AverageFilterInt16_Size3;
typedef AverageFilter<int16_t,int32_t,4> AverageFilterInt16_Size4;
typedef AverageFilter<int16_t,int32_t,5> AverageFilterInt16_Size5;
typedef AverageFilter<uint16_t,uint32_t,2> AverageFilterUInt16_Size2;
typedef AverageFilter<uint16_t,uint32_t,3> AverageFilterUInt16_Size3;
typedef AverageFilter<uint16_t,uint32_t,4> AverageFilterUInt16_Size4;
typedef AverageFilter<uint16_t,uint32_t,5> AverageFilterUInt16_Size5;
typedef AverageFilter<int32_t,float,2> AverageFilterInt32_Size2;
typedef AverageFilter<int32_t,float,3> AverageFilterInt32_Size3;
typedef AverageFilter<int32_t,float,4> AverageFilterInt32_Size4;
typedef AverageFilter<int32_t,float,5> AverageFilterInt32_Size5;
typedef AverageFilter<uint32_t,float,2> AverageFilterUInt32_Size2;
typedef AverageFilter<uint32_t,float,3> AverageFilterUInt32_Size3;
typedef AverageFilter<uint32_t,float,4> AverageFilterUInt32_Size4;
typedef AverageFilter<uint32_t,float,5> AverageFilterUInt32_Size5;
// Public Methods //////////////////////////////////////////////////////////////
template <class T, class U>
T AverageFilter<T,U>::apply(T sample)
template <class T, class U, uint8_t FILTER_SIZE>
T AverageFilter<T,U,FILTER_SIZE>::apply(T sample)
{
U result = 0;
// call parent's apply function to get the sample into the array
Filter<T>::apply(sample);
FilterWithBuffer<T,FILTER_SIZE>::apply(sample);
// increment the number of samples so far
_num_samples++;
if( _num_samples > Filter<T>::filter_size || _num_samples == 0 )
_num_samples = Filter<T>::filter_size;
if( _num_samples > FILTER_SIZE || _num_samples == 0 )
_num_samples = FILTER_SIZE;
// get sum of all values - there is a risk of overflow here that we ignore
for(int8_t i=0; i<Filter<T>::filter_size; i++)
result += Filter<T>::samples[i];
for(uint8_t i=0; i<FILTER_SIZE; i++)
result += FilterWithBuffer<T,FILTER_SIZE>::samples[i];
return (T)(result / _num_samples);
}
// reset - clear all samples
template <class T, class U>
void AverageFilter<T,U>::reset()
template <class T, class U, uint8_t FILTER_SIZE>
void AverageFilter<T,U,FILTER_SIZE>::reset()
{
// call parent's apply function to get the sample into the array
Filter<T>::reset();
FilterWithBuffer<T,FILTER_SIZE>::reset();
// clear our variable
_num_samples = 0;
}
#endif

View File

@ -7,9 +7,8 @@
//
/// @file Filter.h
/// @brief A base class for apply various filters to values
/// @brief A base class from which various filters classes should inherit
///
/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION
#ifndef Filter_h
#define Filter_h
@ -17,79 +16,28 @@
#include <inttypes.h>
#include <AP_Common.h>
#define FILTER_MAX_SAMPLES 10 // maximum size of the sample buffer (normally older values will be overwritten as new appear)
template <class T>
class Filter
{
public:
Filter(uint8_t requested_size);
~Filter();
// constructor
Filter() {};
// apply - Add a new raw value to the filter, retrieve the filtered result
virtual T apply(T sample);
virtual T apply(T sample) { return sample; };
// reset - clear the filter
virtual void reset();
virtual void reset() {};
uint8_t filter_size; // max number of items in filter
T* samples; // buffer of samples
uint8_t sample_index; // pointer to the next empty slot in the buffer
private:
};
// Typedef for convenience
typedef Filter<int8_t> FilterInt8;
typedef Filter<uint8_t> FilterUInt8;
typedef Filter<int16_t> FilterInt16;
// Constructor
template <class T>
Filter<T>::Filter(uint8_t requested_size) :
filter_size(requested_size), sample_index(0)
{
// check filter size
if( Filter<T>::filter_size > FILTER_MAX_SAMPLES )
Filter<T>::filter_size = FILTER_MAX_SAMPLES;
// create array
samples = (T *)malloc(Filter<T>::filter_size * sizeof(T));
// clear array
reset();
}
// Destructor - THIS SHOULD NEVER BE CALLED OR IT COULD LEAD TO MEMORY FRAGMENTATION
template <class T>
Filter<T>::~Filter()
{
// free up the samples array
free(samples);
}
// reset - clear all samples
template <class T>
void Filter<T>::reset()
{
for( int8_t i=0; i<filter_size; i++ ) {
samples[i] = 0;
}
sample_index = 0;
}
// apply - take in a new raw sample, and return the filtered results
template <class T>
T Filter<T>::apply(T sample){
// add sample to array
samples[sample_index++] = sample;
// wrap index if necessary
if( sample_index >= filter_size )
sample_index = 0;
// base class doesn't know what filtering to do so we just return the raw sample
return sample;
}
typedef Filter<uint16_t> FilterUInt16;
typedef Filter<int32_t> FilterInt32;
typedef Filter<uint32_t> FilterUInt32;
#endif

View File

@ -0,0 +1,102 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
// This is free software; you can redistribute it and/or modify it under
// the terms of the GNU Lesser General Public License as published by the
// Free Software Foundation; either version 2.1 of the License, or (at
// your option) any later version.
//
/// @file FilterWithBuffer.h
/// @brief A filter with a buffer.
/// This is implemented separately to the base Filter class to get around
/// restrictions caused by the use of templates which makes different sizes essentially
/// completely different classes
#ifndef FilterWithBuffer_h
#define FilterWithBuffer_h
#include <inttypes.h>
#include <AP_Common.h>
#include <Filter.h>
template <class T, uint8_t FILTER_SIZE>
class FilterWithBuffer : public Filter<T>
{
public:
// constructor
FilterWithBuffer();
// apply - Add a new raw value to the filter, retrieve the filtered result
virtual T apply(T sample);
// reset - clear the filter
virtual void reset();
// get filter size
virtual uint8_t get_filter_size() { return FILTER_SIZE; };
T samples[FILTER_SIZE]; // buffer of samples
uint8_t sample_index; // pointer to the next empty slot in the buffer
private:
};
// Typedef for convenience
typedef FilterWithBuffer<int16_t,2> FilterWithBufferInt16_Size2;
typedef FilterWithBuffer<int16_t,3> FilterWithBufferInt16_Size3;
typedef FilterWithBuffer<int16_t,4> FilterWithBufferInt16_Size4;
typedef FilterWithBuffer<int16_t,5> FilterWithBufferInt16_Size5;
typedef FilterWithBuffer<int16_t,6> FilterWithBufferInt16_Size6;
typedef FilterWithBuffer<int16_t,7> FilterWithBufferInt16_Size7;
typedef FilterWithBuffer<uint16_t,2> FilterWithBufferUInt16_Size2;
typedef FilterWithBuffer<uint16_t,3> FilterWithBufferUInt16_Size3;
typedef FilterWithBuffer<uint16_t,4> FilterWithBufferUInt16_Size4;
typedef FilterWithBuffer<uint16_t,5> FilterWithBufferUInt16_Size5;
typedef FilterWithBuffer<uint16_t,6> FilterWithBufferUInt16_Size6;
typedef FilterWithBuffer<uint16_t,7> FilterWithBufferUInt16_Size7;
// Constructor
template <class T, uint8_t FILTER_SIZE>
FilterWithBuffer<T,FILTER_SIZE>::FilterWithBuffer() :
Filter<T>(),
sample_index(0)
{
// clear sample buffer
reset();
}
// reset - clear all samples from the buffer
template <class T, uint8_t FILTER_SIZE>
void FilterWithBuffer<T,FILTER_SIZE>::reset()
{
// call base class reset
Filter<T>::reset();
// clear samples buffer
for( int8_t i=0; i<FILTER_SIZE; i++ ) {
samples[i] = 0;
}
// reset index back to beginning of the array
sample_index = 0;
}
// apply - take in a new raw sample, and return the filtered results
template <class T, uint8_t FILTER_SIZE>
T FilterWithBuffer<T,FILTER_SIZE>::apply(T sample)
{
// add sample to array
samples[sample_index++] = sample;
// wrap index if necessary
if( sample_index >= FILTER_SIZE )
sample_index = 0;
// base class doesn't know what filtering to do so we just return the raw sample
return sample;
}
#endif

View File

@ -17,12 +17,13 @@
#include <inttypes.h>
#include <Filter.h>
#include <FilterWithBuffer.h>
template <class T>
class ModeFilter : public Filter<T>
template <class T, uint8_t FILTER_SIZE>
class ModeFilter : public FilterWithBuffer<T,FILTER_SIZE>
{
public:
ModeFilter(uint8_t requested_size, uint8_t return_element);
ModeFilter(uint8_t return_element);
// apply - Add a new raw value to the filter, retrieve the filtered result
virtual T apply(T sample);
@ -35,25 +36,44 @@ class ModeFilter : public Filter<T>
};
// Typedef for convenience
typedef ModeFilter<int16_t> ModeFilterInt16;
typedef ModeFilter<int8_t,3> ModeFilterInt8_Size3;
typedef ModeFilter<int8_t,4> ModeFilterInt8_Size4;
typedef ModeFilter<int8_t,5> ModeFilterInt8_Size5;
typedef ModeFilter<int8_t,6> ModeFilterInt8_Size6;
typedef ModeFilter<int8_t,7> ModeFilterInt8_Size7;
typedef ModeFilter<uint8_t,3> ModeFilterUInt8_Size3;
typedef ModeFilter<uint8_t,4> ModeFilterUInt8_Size4;
typedef ModeFilter<uint8_t,5> ModeFilterUInt8_Size5;
typedef ModeFilter<uint8_t,6> ModeFilterUInt8_Size6;
typedef ModeFilter<uint8_t,7> ModeFilterUInt8_Size7;
typedef ModeFilter<int16_t,3> ModeFilterInt16_Size3;
typedef ModeFilter<int16_t,4> ModeFilterInt16_Size4;
typedef ModeFilter<int16_t,5> ModeFilterInt16_Size5;
typedef ModeFilter<int16_t,6> ModeFilterInt16_Size6;
typedef ModeFilter<int16_t,7> ModeFilterInt16_Size7;
typedef ModeFilter<uint16_t,3> ModeFilterUInt16_Size3;
typedef ModeFilter<uint16_t,4> ModeFilterUInt16_Size4;
typedef ModeFilter<uint16_t,5> ModeFilterUInt16_Size5;
typedef ModeFilter<uint16_t,6> ModeFilterUInt16_Size6;
typedef ModeFilter<uint16_t,7> ModeFilterUInt16_Size7;
// Constructor //////////////////////////////////////////////////////////////
template <class T>
ModeFilter<T>::ModeFilter(uint8_t requested_size, uint8_t return_element) :
Filter<T>(requested_size),
template <class T, uint8_t FILTER_SIZE>
ModeFilter<T,FILTER_SIZE>::ModeFilter(uint8_t return_element) :
FilterWithBuffer<T,FILTER_SIZE>(),
_return_element(return_element),
drop_high_sample(true)
{
// ensure we have a valid return_nth_element value. if not, revert to median
if( _return_element >= Filter<T>::filter_size )
_return_element = Filter<T>::filter_size / 2;
if( _return_element >= FILTER_SIZE )
_return_element = FILTER_SIZE / 2;
};
// Public Methods //////////////////////////////////////////////////////////////
template <class T>
T ModeFilter<T>::apply(T sample)
template <class T, uint8_t FILTER_SIZE>
T ModeFilter<T,FILTER_SIZE>::apply(T sample)
{
// insert the new items into the samples buffer
isort(sample, drop_high_sample);
@ -62,12 +82,12 @@ T ModeFilter<T>::apply(T sample)
drop_high_sample = !drop_high_sample;
// return results
if( Filter<T>::sample_index < Filter<T>::filter_size ) {
if( FilterWithBuffer<T,FILTER_SIZE>::sample_index < FILTER_SIZE ) {
// middle sample if buffer is not yet full
return Filter<T>::samples[(Filter<T>::sample_index / 2)];
return FilterWithBuffer<T,FILTER_SIZE>::samples[(FilterWithBuffer<T,FILTER_SIZE>::sample_index / 2)];
}else{
// return element specified by user in constructor
return Filter<T>::samples[_return_element];
return FilterWithBuffer<T,FILTER_SIZE>::samples[_return_element];
}
}
@ -75,31 +95,31 @@ T ModeFilter<T>::apply(T sample)
// insertion sort - takes a new sample and pushes it into the sample array
// drops either the highest or lowest sample depending on the 'drop_high_sample' parameter
//
template <class T>
void ModeFilter<T>::isort(T new_sample, bool drop_high)
template <class T, uint8_t FILTER_SIZE>
void ModeFilter<T,FILTER_SIZE>::isort(T new_sample, bool drop_high)
{
int8_t i;
// if the buffer isn't full simply increase the #items in the buffer (i.e. sample_index)
// the rest is the same as dropping the high sample
if( Filter<T>::sample_index < Filter<T>::filter_size ) {
Filter<T>::sample_index++;
if( FilterWithBuffer<T,FILTER_SIZE>::sample_index < FILTER_SIZE ) {
FilterWithBuffer<T,FILTER_SIZE>::sample_index++;
drop_high = true;
}
if( drop_high ) { // drop highest sample from the buffer to make room for our new sample
// start from top. Note: sample_index always points to the next open space so we start from sample_index-1
i = Filter<T>::sample_index-1;
i = FilterWithBuffer<T,FILTER_SIZE>::sample_index-1;
// if the next element is higher than our new sample, push it up one position
while( Filter<T>::samples[i-1] > new_sample && i > 0 ) {
Filter<T>::samples[i] = Filter<T>::samples[i-1];
while( FilterWithBuffer<T,FILTER_SIZE>::samples[i-1] > new_sample && i > 0 ) {
FilterWithBuffer<T,FILTER_SIZE>::samples[i] = FilterWithBuffer<T,FILTER_SIZE>::samples[i-1];
i--;
}
// add our new sample to the buffer
Filter<T>::samples[i] = new_sample;
FilterWithBuffer<T,FILTER_SIZE>::samples[i] = new_sample;
}else{ // drop lowest sample from the buffer to make room for our new sample
@ -107,17 +127,14 @@ void ModeFilter<T>::isort(T new_sample, bool drop_high)
i = 0;
// if the element is lower than our new sample, push it down one position
while( Filter<T>::samples[i+1] < new_sample && i < Filter<T>::sample_index-1 ) {
Filter<T>::samples[i] = Filter<T>::samples[i+1];
while( FilterWithBuffer<T,FILTER_SIZE>::samples[i+1] < new_sample && i < FilterWithBuffer<T,FILTER_SIZE>::sample_index-1 ) {
FilterWithBuffer<T,FILTER_SIZE>::samples[i] = FilterWithBuffer<T,FILTER_SIZE>::samples[i+1];
i++;
}
// add our new sample to the buffer
Filter<T>::samples[i] = new_sample;
FilterWithBuffer<T,FILTER_SIZE>::samples[i] = new_sample;
}
}
#endif

View File

@ -1,54 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
// This is free software; you can redistribute it and/or modify it under
// the terms of the GNU Lesser General Public License as published by the
// Free Software Foundation; either version 2.1 of the License, or (at
// your option) any later version.
//
/// @file SumFilter.h
/// @brief A class to apply an average filter (but we save some calc time by not averaging the values but instead save one division by just adding the values up
///
/// DO NOT CREATE AND DESTROY INSTANCES OF THIS CLASS BECAUSE THE ALLOC/MALLOC WILL LEAD TO MEMORY FRAGMENTATION
#ifndef SumFilter_h
#define SumFilter_h
#include <inttypes.h>
#include <Filter.h>
template <class T>
class SumFilter : public Filter<T>
{
public:
SumFilter(uint8_t requested_size) : Filter<T>(requested_size) {};
// apply - Add a new raw value to the filter, retrieve the filtered result
virtual T apply(T sample);
private:
};
// Typedef for convenience
typedef SumFilter<int16_t> SumFilterInt16;
// Public Methods //////////////////////////////////////////////////////////////
template <class T>
T SumFilter<T>::apply(T sample){
T result = 0;
// call parent's apply function to get the sample into the array
Filter<T>::apply(sample);
// get sum of all values - there is a risk of overflow here that we ignore
for(int8_t i=0; i<Filter<T>::filter_size; i++)
result += Filter<T>::samples[i];
return result;
}
#endif

View File

@ -1,8 +1,9 @@
Filter KEYWORD1
FilterWithBuffer KEYWORD1
ModeFilter KEYWORD1
SumFilter KEYWORD1
AverageFilter KEYWORD1
apply KEYWORD2
reset KEYWORD2
max_samples KEYWORD2
get_filter_size KEYWORD2
samples KEYWORD2
sample_index KEYWORD2