mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/Filter/DerivativeFilter.h
This commit is contained in:
parent
973dcba9ab
commit
6bfccd13f8
|
@ -22,26 +22,27 @@
|
|||
template <class T, uint8_t FILTER_SIZE>
|
||||
class DerivativeFilter : public FilterWithBuffer<T,FILTER_SIZE>
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
DerivativeFilter() : FilterWithBuffer<T,FILTER_SIZE>() {};
|
||||
public:
|
||||
// constructor
|
||||
DerivativeFilter() : FilterWithBuffer<T,FILTER_SIZE>() {
|
||||
};
|
||||
|
||||
// update - Add a new raw value to the filter, but don't recalculate
|
||||
virtual void update(T sample, uint32_t timestamp);
|
||||
// update - Add a new raw value to the filter, but don't recalculate
|
||||
virtual void update(T sample, uint32_t timestamp);
|
||||
|
||||
// return the derivative value
|
||||
virtual float slope(void);
|
||||
// return the derivative value
|
||||
virtual float slope(void);
|
||||
|
||||
// reset - clear the filter
|
||||
virtual void reset();
|
||||
// reset - clear the filter
|
||||
virtual void reset();
|
||||
|
||||
private:
|
||||
bool _new_data;
|
||||
float _last_slope;
|
||||
private:
|
||||
bool _new_data;
|
||||
float _last_slope;
|
||||
|
||||
// microsecond timestamps for samples. This is needed
|
||||
// to cope with non-uniform time spacing of the data
|
||||
uint32_t _timestamps[FILTER_SIZE];
|
||||
uint32_t _timestamps[FILTER_SIZE];
|
||||
};
|
||||
|
||||
typedef DerivativeFilter<float,5> DerivativeFilterFloat_Size5;
|
||||
|
|
Loading…
Reference in New Issue