mad-location-manager-lib 1.0
Library for fusing GPS and ENU accelerometer data
Loading...
Searching...
No Matches
Public Member Functions | Private Attributes | List of all members
MLM Class Reference

Motion Location Model - GPS/Accelerometer sensor fusion estimator. More...

#include <mlm.h>

Public Member Functions

 MLM (void)
 Default constructor with standard noise parameters.
 
 MLM (double acc_sigma_2, double loc_sigma_2, double vel_sigma_2)
 Constructor with custom noise parameters.
 
 ~MLM (void)
 Destructor.
 
bool process_acc_data (const enu_accelerometer &acc, double time_sec)
 Process accelerometer measurement (prediction step)
 
void process_gps_data (const gps_coordinate &gps, double time_sec)
 Process GPS measurement (update step)
 
gps_coordinate predicted_coordinate () const
 Get current estimated position.
 

Private Attributes

gps_acc_fusion_filter m_fk
 Kalman filter for GPS-accelerometer fusion.
 
GeographicLib::LocalCartesian m_lc
 Local cartesian coordinate converter.
 
bool m_got_start_point
 Flag indicating if initial reference point is set.
 
double m_acc_sigma_2
 Accelerometer noise variance [m²/s⁴].
 
double m_loc_sigma_2
 Location measurement noise variance [m²].
 
double m_vel_sigma_2
 Velocity process noise variance [m²/s²].
 

Detailed Description

Motion Location Model - GPS/Accelerometer sensor fusion estimator.

This class implements a Kalman filter-based sensor fusion system that combines GPS position measurements with accelerometer data to provide improved position and velocity estimates. The system uses ENU (East-North-Up) coordinate frame for local calculations and converts to/from geographic coordinates.

The filter operates in predict-update cycles:

Noise characteristics are configurable via sigma-squared parameters for accelerometer, location, and velocity uncertainties.

Constructor & Destructor Documentation

◆ MLM() [1/2]

MLM::MLM ( void  )

Default constructor with standard noise parameters.

◆ MLM() [2/2]

MLM::MLM ( double  acc_sigma_2,
double  loc_sigma_2,
double  vel_sigma_2 
)

Constructor with custom noise parameters.

Parameters
acc_sigma_2Accelerometer noise variance [m²/s⁴]
loc_sigma_2Location measurement noise variance [m²]
vel_sigma_2Velocity process noise variance [m²/s²]

◆ ~MLM()

MLM::~MLM ( void  )

Destructor.

Member Function Documentation

◆ predicted_coordinate()

gps_coordinate MLM::predicted_coordinate ( ) const

Get current estimated position.

Returns
Predicted GPS coordinate based on current filter state

◆ process_acc_data()

bool MLM::process_acc_data ( const enu_accelerometer acc,
double  time_sec 
)

Process accelerometer measurement (prediction step)

Propagates the filter state forward using accelerometer data as control input. This performs the prediction step of the Kalman filter.

Parameters
accENU-frame accelerometer measurement
time_secTimestamp in seconds
Returns
true if processing successful, false otherwise

◆ process_gps_data()

void MLM::process_gps_data ( const gps_coordinate gps,
double  time_sec 
)

Process GPS measurement (update step)

Corrects the predicted state using GPS position measurement. This performs the update/correction step of the Kalman filter.

Parameters
gpsGPS coordinate measurement
time_secTimestamp in seconds

Member Data Documentation

◆ m_acc_sigma_2

double MLM::m_acc_sigma_2
private

Accelerometer noise variance [m²/s⁴].

◆ m_fk

gps_acc_fusion_filter MLM::m_fk
private

Kalman filter for GPS-accelerometer fusion.

◆ m_got_start_point

bool MLM::m_got_start_point
private

Flag indicating if initial reference point is set.

◆ m_lc

GeographicLib::LocalCartesian MLM::m_lc
private

Local cartesian coordinate converter.

◆ m_loc_sigma_2

double MLM::m_loc_sigma_2
private

Location measurement noise variance [m²].

◆ m_vel_sigma_2

double MLM::m_vel_sigma_2
private

Velocity process noise variance [m²/s²].


The documentation for this class was generated from the following files: