|
mad-location-manager-lib 1.0
Library for fusing GPS and ENU accelerometer data
|
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²]. | |
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.
| MLM::MLM | ( | void | ) |
Default constructor with standard noise parameters.
Constructor with custom noise parameters.
| acc_sigma_2 | Accelerometer noise variance [m²/s⁴] |
| loc_sigma_2 | Location measurement noise variance [m²] |
| vel_sigma_2 | Velocity process noise variance [m²/s²] |
| MLM::~MLM | ( | void | ) |
Destructor.
| gps_coordinate MLM::predicted_coordinate | ( | ) | const |
Get current estimated position.
| 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.
| acc | ENU-frame accelerometer measurement |
| time_sec | Timestamp in seconds |
| 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.
| gps | GPS coordinate measurement |
| time_sec | Timestamp in seconds |
|
private |
Accelerometer noise variance [m²/s⁴].
|
private |
Kalman filter for GPS-accelerometer fusion.
|
private |
Flag indicating if initial reference point is set.
|
private |
Local cartesian coordinate converter.
|
private |
Location measurement noise variance [m²].
|
private |
Velocity process noise variance [m²/s²].