mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
FilterWithBuffer: make get_sample non-virtual
virtual added to apply() and reset() declaration inline with base class. This should have no impact on memory usage or functionality
This commit is contained in:
parent
6cee33b6fd
commit
4040be9990
@ -34,17 +34,17 @@ public:
|
||||
FilterWithBuffer();
|
||||
|
||||
// apply - Add a new raw value to the filter, retrieve the filtered result
|
||||
T apply(T sample);
|
||||
virtual T apply(T sample);
|
||||
|
||||
// reset - clear the filter
|
||||
void reset();
|
||||
virtual void reset();
|
||||
|
||||
// get filter size
|
||||
uint8_t get_filter_size() const {
|
||||
return FILTER_SIZE;
|
||||
};
|
||||
|
||||
virtual T get_sample(uint8_t i) const {
|
||||
T get_sample(uint8_t i) const {
|
||||
return samples[i];
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user