LowPassFilter: add get method

This commit is contained in:
Randy Mackay 2015-06-11 22:17:11 +09:00
parent 0db7acc628
commit 1289208244
1 changed files with 9 additions and 0 deletions

View File

@ -158,6 +158,15 @@ public:
return ret;
}
// get latest filtered value from filter (equal to the value returned by latest call to apply method)
Vector3f get() const {
Vector3f ret;
ret.x = _filter_x.get();
ret.y = _filter_y.get();
ret.z = _filter_z.get();
return ret;
}
void reset(const Vector3f& value) {
_filter_x.reset(value.x);
_filter_y.reset(value.y);