extended_kalman_filter.h 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177
  1. /*
  2. * @Descripttion: extendedKalmanFilter.h Project
  3. * @version: Project v0.1
  4. * @Author: lenotary
  5. * @Date: 2020/11/18 下午2:59
  6. * @LastEditor: lenotary
  7. * @LastEditTime: 2020/11/18 下午2:59
  8. */
  9. #ifndef SRC_EXTENDED_KALMAN_FILTER_H
  10. #define SRC_EXTENDED_KALMAN_FILTER_H
  11. #include <Eigen/Dense>
  12. #include <nav_msgs/Odometry.h>
  13. #include "common.h"
  14. #include <queue>
  15. #include "tf/tf.h"
  16. struct OdomInfo {
  17. nav_msgs::Odometry odom;
  18. Eigen::VectorXd x;
  19. };
  20. class ExtendedKalmanFilter {
  21. public:
  22. void Initialize(geometry_msgs::Pose pose, double time) {
  23. Eigen::MatrixXd x(3, 1);
  24. double angle = tf::getYaw(pose.orientation);
  25. x << pose.position.x, pose.position.y, angle;
  26. x_ = x;
  27. odomTimeStamp_ = time;
  28. Eigen::MatrixXd F(3, 3);
  29. F << 1, 0, 0,
  30. 0, 1, 0,
  31. 0, 0, 1;
  32. SetF(F);
  33. Eigen::MatrixXd FJ(3, 3);
  34. FJ << 1, 0, 0,
  35. 0, 1, 0,
  36. 0, 0, 1;
  37. SetFJ(FJ);
  38. Eigen::MatrixXd P(3, 3);
  39. P << 1, 0, 0,
  40. 0, 1, 0,
  41. 0, 0, 100;
  42. SetP(P);
  43. Eigen::MatrixXd Q(3, 3);
  44. Q << 1, 0, 0,
  45. 0, 1, 0,
  46. 0, 0, 1;
  47. SetQ(Q);
  48. Eigen::MatrixXd H(3, 3);
  49. H << 1, 0, 0,
  50. 0, 1, 0,
  51. 0, 0, 1;
  52. SetH(H);
  53. Eigen::MatrixXd R(3, 3);
  54. R << 1, 0, 0,
  55. 0, 1, 0,
  56. 0, 0, 1;
  57. SetR(R);
  58. is_initialized_ = true;
  59. }
  60. void SetOdomAngle(double angle_in){
  61. angle_ = angle_in;
  62. }
  63. void SetF(Eigen::MatrixXd F_in) {
  64. F_ = F_in;
  65. }
  66. void SetFJ(Eigen::MatrixXd FJ_in) {
  67. FJ_ = FJ_in;
  68. }
  69. void SetP(Eigen::MatrixXd P_in) {
  70. P_ = P_in;
  71. }
  72. void SetQ(Eigen::MatrixXd Q_in) {
  73. Q_ = Q_in;
  74. }
  75. void SetH(Eigen::MatrixXd H_in) {
  76. H_ = H_in;
  77. }
  78. void SetR(Eigen::MatrixXd R_in) {
  79. R_ = R_in;
  80. }
  81. Eigen::MatrixXd GetX() {
  82. return x_;
  83. }
  84. bool IsInitialized() {
  85. return is_initialized_;
  86. }
  87. void InputOdomMeasurement(nav_msgs::Odometry odom) {
  88. if (odomTimeStamp_ > 1) {
  89. auto dt = odom.header.stamp.toSec() - odomTimeStamp_;
  90. double dz = odom.twist.twist.angular.z * dt;
  91. dz = NormalizeAngle(dz);
  92. double angle = x_(2) + dz + angle_;
  93. double dx = odom.twist.twist.linear.x * cos(angle) * dt;
  94. double dy = odom.twist.twist.linear.x * sin(angle) * dt;
  95. Eigen::Vector3d u_(dx, dy, dz);
  96. Eigen::MatrixXd Fj(3, 3);
  97. Fj << 1, 0, -u_(1),
  98. 0, 1, u_(0),
  99. 0, 0, 1;
  100. SetFJ(Fj);
  101. Prediction(u_);
  102. }
  103. odomTimeStamp_ = odom.header.stamp.toSec();
  104. }
  105. void AddLidarMeasurement(geometry_msgs::PoseStamped pose) {
  106. Eigen::VectorXd z(3, 1);
  107. double angle = tf::getYaw(pose.pose.orientation);
  108. z << pose.pose.position.x, pose.pose.position.y, angle;
  109. zTimeStamp_ = pose.header.stamp.toSec();
  110. MeasurementUpdate(z);
  111. }
  112. void Prediction(Eigen::VectorXd u_) {
  113. x_ = F_ * x_ + u_;
  114. Eigen::MatrixXd Ft = FJ_.transpose();
  115. P_ = FJ_ * P_ * Ft + Q_;
  116. }
  117. void MeasurementUpdate(const Eigen::VectorXd &z) {
  118. Eigen::VectorXd y = z - H_ * x_;
  119. y(2) = NormalizeAngle(y(2));
  120. // std::cout << " H " << H_ << std::endl;
  121. // std::cout << " P " << P_ << std::endl;
  122. // std::cout << " Ht " << H_.transpose() << std::endl;
  123. // std::cout << " R " << R_ << std::endl;
  124. Eigen::MatrixXd S = H_ * P_ * H_.transpose() + R_;
  125. Eigen::MatrixXd K = P_ * H_.transpose() * S.inverse();
  126. // std::cout << " Y " << std::endl << y.transpose() << std::endl;
  127. // std::cout << " K " << std::endl << K << std::endl;
  128. // ROS_INFO("info %f %f", odomTimeStamp_, zTimeStamp_);
  129. // std::cout << "info " << std::endl
  130. // << K << std::endl;
  131. x_ = x_ + (K * y);
  132. int size = x_.size();
  133. Eigen::MatrixXd I = Eigen::MatrixXd::Identity(size, size);
  134. P_ = (I - K * H_) * P_;
  135. }
  136. private:
  137. bool is_initialized_{false};
  138. Eigen::VectorXd x_;
  139. Eigen::MatrixXd F_;
  140. Eigen::MatrixXd FJ_;
  141. Eigen::MatrixXd P_;
  142. Eigen::MatrixXd Q_;
  143. Eigen::MatrixXd H_;
  144. Eigen::MatrixXd R_;
  145. double angle_{0.0};
  146. double odomTimeStamp_;
  147. double zTimeStamp_;
  148. };
  149. #endif //SRC_EXTENDED_KALMAN_FILTER_H