From 520d762382eab783f081440f1f5bb61fec3583cb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 6 Jul 2012 15:04:54 +1000 Subject: [PATCH] Filter: split the DerivativeFilter steps into update() and slope() this allows us to apply new data at a different rate than we calculate the slope. --- libraries/Filter/DerivativeFilter.cpp | 20 ++++++++++++++------ libraries/Filter/DerivativeFilter.h | 7 +++++-- 2 files changed, 19 insertions(+), 8 deletions(-) diff --git a/libraries/Filter/DerivativeFilter.cpp b/libraries/Filter/DerivativeFilter.cpp index 4a796f9b32..817bd0a64f 100644 --- a/libraries/Filter/DerivativeFilter.cpp +++ b/libraries/Filter/DerivativeFilter.cpp @@ -16,15 +16,20 @@ #include template -float DerivativeFilter::apply(T sample, uint32_t timestamp) +void DerivativeFilter::update(T sample, uint32_t timestamp) { - float result = 0; - // add timestamp before we apply to FilterWithBuffer _timestamps[FilterWithBuffer::sample_index] = timestamp; // call parent's apply function to get the sample into the array FilterWithBuffer::apply(sample); +} + + +template +float DerivativeFilter::slope(void) +{ + float result = 0; // use f() to make the code match the maths a bit better. Note // that unlike an average filter, we care about the order of the elements @@ -81,13 +86,16 @@ void DerivativeFilter::reset(void) } // add new instances as needed here -template float DerivativeFilter::apply(float sample, uint32_t timestamp); +template void DerivativeFilter::update(float sample, uint32_t timestamp); +template float DerivativeFilter::slope(void); template void DerivativeFilter::reset(void); -template float DerivativeFilter::apply(float sample, uint32_t timestamp); +template void DerivativeFilter::update(float sample, uint32_t timestamp); +template float DerivativeFilter::slope(void); template void DerivativeFilter::reset(void); -template float DerivativeFilter::apply(float sample, uint32_t timestamp); +template void DerivativeFilter::update(float sample, uint32_t timestamp); +template float DerivativeFilter::slope(void); template void DerivativeFilter::reset(void); diff --git a/libraries/Filter/DerivativeFilter.h b/libraries/Filter/DerivativeFilter.h index 5a6ce1171e..1267a9ba8b 100644 --- a/libraries/Filter/DerivativeFilter.h +++ b/libraries/Filter/DerivativeFilter.h @@ -26,8 +26,11 @@ class DerivativeFilter : public FilterWithBuffer // constructor DerivativeFilter() : FilterWithBuffer() {}; - // apply - Add a new raw value to the filter, retrieve the filtered result - virtual float apply(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); // reset - clear the filter virtual void reset();