Skip to content
This repository has been archived by the owner on May 1, 2024. It is now read-only.

Commit

Permalink
AlphaFilter add constructor that takes alpha and use in EKF
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar authored Dec 16, 2020
1 parent 37e84b7 commit 1237087
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 9 deletions.
14 changes: 11 additions & 3 deletions AlphaFilter/AlphaFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,12 @@
#include <float.h>

template <typename T>
class AlphaFilter {
class AlphaFilter
{
public:
AlphaFilter() = default;
explicit AlphaFilter(float alpha) : _alpha(alpha) {}

~AlphaFilter() = default;

/**
Expand All @@ -58,7 +61,8 @@ class AlphaFilter {
* @param sample_interval interval between two samples
* @param time_constant filter time constant determining convergence
*/
void setParameters(float sample_interval, float time_constant) {
void setParameters(float sample_interval, float time_constant)
{
const float denominator = time_constant + sample_interval;

if (denominator > FLT_EPSILON) {
Expand All @@ -85,7 +89,11 @@ class AlphaFilter {
*
* @return retrieve the filtered result
*/
void update(const T &sample) { _filter_state = updateCalculation(sample); }
const T &update(const T &sample)
{
_filter_state = updateCalculation(sample);
return _filter_state;
}

const T &getState() const { return _filter_state; }

Expand Down
3 changes: 0 additions & 3 deletions EKF/ekf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,6 @@ bool Ekf::init(uint64_t timestamp)
{
bool ret = initialise_interface(timestamp);
reset();
_accel_lpf.setAlpha(.1f);
_gyro_lpf.setAlpha(.1f);
_mag_lpf.setAlpha(.1f);
return ret;
}

Expand Down
6 changes: 3 additions & 3 deletions EKF/ekf.h
Original file line number Diff line number Diff line change
Expand Up @@ -468,11 +468,11 @@ class Ekf final : public EstimatorInterface
bool _is_first_imu_sample{true};
uint32_t _baro_counter{0}; ///< number of baro samples read during initialisation
uint32_t _mag_counter{0}; ///< number of magnetometer samples read during initialisation
AlphaFilter<Vector3f> _accel_lpf; ///< filtered accelerometer measurement used to align tilt (m/s/s)
AlphaFilter<Vector3f> _gyro_lpf; ///< filtered gyro measurement used for alignment excessive movement check (rad/sec)
AlphaFilter<Vector3f> _accel_lpf{0.1f}; ///< filtered accelerometer measurement used to align tilt (m/s/s)
AlphaFilter<Vector3f> _gyro_lpf{0.1f}; ///< filtered gyro measurement used for alignment excessive movement check (rad/sec)

// Variables used to perform in flight resets and switch between height sources
AlphaFilter<Vector3f> _mag_lpf; ///< filtered magnetometer measurement for instant reset (Gauss)
AlphaFilter<Vector3f> _mag_lpf{0.1f}; ///< filtered magnetometer measurement for instant reset (Gauss)
float _hgt_sensor_offset{0.0f}; ///< set as necessary if desired to maintain the same height after a height reset (m)
float _baro_hgt_offset{0.0f}; ///< baro height reading at the local NED origin (m)

Expand Down

0 comments on commit 1237087

Please sign in to comment.