项目作者: AlexanderSilvaB

项目描述 :
Header-only Bayes Filters Library
高级语言: C++
项目地址: git://github.com/AlexanderSilvaB/bflib.git
创建时间: 2019-07-18T08:27:59Z
项目社区:https://github.com/AlexanderSilvaB/bflib

开源协议:MIT License

下载


bflib

Bayesian Filters Library

Build Status

This library allows the fast implementation of linear and non-linear system predictors based on Bayesian Filters

Examples

Aircraft takeoff (Linear Kalman Filter): linear_aircraft.cpp Aircraft takeoff (Extended Kalman Filter): non_linear_aircraft.cpp
Aircraft takeoff linear example Aircraft takeoff non-linear example
Pendulum (Extended Kalman Filter): pendulum.cpp Sine wave prediction (Extended Kalman Filter): sine.cpp
Pendulum Sine
Robot localization (Extended Kalman Filter): robot_localization_ekf.cpp Robot localization (Particles Filter): robot_localization_pf.cpp
Robot Localization Kalman Robot Localization Monte Carlo

Features

  • Linear Kalman Filter
  • Extended Kalman Filter
  • Particles Filter ( Monte Carlo )
  • Simulate process and sensors
  • Time features
  • Access to state uncertainty
  • Built-in data association
  • Easy integration ( Header-Only )
  • Optimized for speed
  • Eigen as the only dependecy for the library (Samples may use LibPython and OpenCV for data visualization )

To-do

  • Unscented Kalman Filter
  • Better documentation

Example code

This example shows how to predict an aircraft altitude and speed during a takeoff using an approximated linear system. This process can be described by the following set of equations:




These equations can be rewritten as a system of state-space linear equations:



  1. #include <bflib/KF.hpp>
  2. #include <iostream>
  3. using namespace std;
  4. typedef KF<float, 2, 1, 1> Aircraft;
  5. // The process model
  6. void process(Aircraft::StateMatrix &A, Aircraft::InputMatrix &B, Aircraft::OutputMatrix &C, double dt)
  7. {
  8. // Fills the A, B and C matrixes of the process
  9. A << 1, dt,
  10. 0, 1;
  11. B << (dt*dt)/2.0,
  12. dt;
  13. C << 1, 0;
  14. }
  15. int main(int argc, char *argv[])
  16. {
  17. // The system standard deviation
  18. float sigma_x_s = 0.01; // std for position
  19. float sigma_x_v = 0.02; // std for speed
  20. float sigma_y_s = 5.0; // std for position sensor
  21. // Creates a linear kalman filter with float data type, 2 states, 1 input and 1 output
  22. Aircraft kf;
  23. // Sets the process
  24. kf.setProcess(process);
  25. // Creates a new process covariance matrix Q
  26. Aircraft::ModelCovariance Q;
  27. // Fills the Q matrix
  28. Q << sigma_x_s*sigma_x_s, sigma_x_s*sigma_x_v,
  29. sigma_x_v*sigma_x_s, sigma_x_v*sigma_x_v;
  30. // Sets the new Q to the KF
  31. kf.setQ(Q);
  32. // Creates a new sensor covariance matrix R
  33. Aircraft::SensorCovariance R;
  34. // Fills the R matrix
  35. R << sigma_y_s*sigma_y_s;
  36. // Sets the new R to the KF
  37. kf.setR(R);
  38. // Creates two states vectors, one for the simulation and one for the kalman output
  39. Aircraft::State x, xK;
  40. // Creates an input vector and fills it
  41. Aircraft::Input u;
  42. u << 0.1;
  43. // Creates an output vector
  44. Aircraft::Output y;
  45. // Defines the simulation max time and the sample time
  46. float T = 30;
  47. float dt = 0.1;
  48. // Creates a variable to hold the time
  49. float t = 0;
  50. while (t < T)
  51. {
  52. // Simulate the system in order to obtain the sensor reading (y).
  53. // It is not needed on a real system
  54. kf.simulate(x, y, u, dt);
  55. // Run the kalman filter
  56. kf.run(xK, y, u, dt);
  57. // Prints the predicted state
  58. cout << xK << endl;
  59. // Increments the simulation time
  60. t += dt;
  61. }
  62. return 0;
  63. }