mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
DerivativeFilter: update and slope non-virtual
No classes inherit from DerivativeFilter so no need to be virtual. Saves 4bytes of RAM.
This commit is contained in:
parent
4040be9990
commit
38222d65e9
@ -36,10 +36,10 @@ public:
|
||||
};
|
||||
|
||||
// update - Add a new raw value to the filter, but don't recalculate
|
||||
virtual void update(T sample, uint32_t timestamp);
|
||||
void update(T sample, uint32_t timestamp);
|
||||
|
||||
// return the derivative value
|
||||
virtual float slope(void);
|
||||
float slope(void);
|
||||
|
||||
// reset - clear the filter
|
||||
virtual void reset();
|
||||
|
Loading…
Reference in New Issue
Block a user