common_lib.h 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260
  1. #ifndef COMMON_LIB_H
  2. #define COMMON_LIB_H
  3. #include <so3_math.h>
  4. #include <Eigen/Eigen>
  5. #include <pcl/point_types.h>
  6. #include <pcl/point_cloud.h>
  7. #include <fast_lio_sam/Pose6D.h>
  8. #include <sensor_msgs/Imu.h>
  9. #include <nav_msgs/Odometry.h>
  10. #include <tf/transform_broadcaster.h>
  11. #include <eigen_conversions/eigen_msg.h>
  12. using namespace std;
  13. using namespace Eigen;
  14. #define USE_IKFOM
  15. #define PI_M (3.14159265358)
  16. #define G_m_s2 (9.81) // Gravaty const in GuangDong/China
  17. #define DIM_STATE (18) // Dimension of states (Let Dim(SO(3)) = 3)
  18. #define DIM_PROC_N (12) // Dimension of process noise (Let Dim(SO(3)) = 3)
  19. #define CUBE_LEN (6.0)
  20. #define LIDAR_SP_LEN (2)
  21. #define INIT_COV (1)
  22. #define NUM_MATCH_POINTS (5)
  23. #define MAX_MEAS_DIM (10000)
  24. #define VEC_FROM_ARRAY(v) v[0],v[1],v[2]
  25. #define MAT_FROM_ARRAY(v) v[0],v[1],v[2],v[3],v[4],v[5],v[6],v[7],v[8]
  26. #define CONSTRAIN(v,min,max) ((v>min)?((v<max)?v:max):min)
  27. #define ARRAY_FROM_EIGEN(mat) mat.data(), mat.data() + mat.rows() * mat.cols()
  28. #define STD_VEC_FROM_EIGEN(mat) vector<decltype(mat)::Scalar> (mat.data(), mat.data() + mat.rows() * mat.cols())
  29. #define DEBUG_FILE_DIR(name) (string(string(ROOT_DIR) + "Log/"+ name))
  30. typedef fast_lio_sam::Pose6D Pose6D;
  31. typedef pcl::PointXYZINormal PointType;
  32. typedef pcl::PointCloud<PointType> PointCloudXYZI;
  33. typedef vector<PointType, Eigen::aligned_allocator<PointType>> PointVector;
  34. typedef Vector3d V3D;
  35. typedef Matrix3d M3D;
  36. typedef Vector3f V3F;
  37. typedef Matrix3f M3F;
  38. #define MD(a,b) Matrix<double, (a), (b)>
  39. #define VD(a) Matrix<double, (a), 1>
  40. #define MF(a,b) Matrix<float, (a), (b)>
  41. #define VF(a) Matrix<float, (a), 1>
  42. M3D Eye3d(M3D::Identity());
  43. M3F Eye3f(M3F::Identity());
  44. V3D Zero3d(0, 0, 0);
  45. V3F Zero3f(0, 0, 0);
  46. // 储存一帧lidar数据及imu数据序列
  47. struct MeasureGroup // Lidar data and imu dates for the curent process
  48. {
  49. MeasureGroup()
  50. {
  51. lidar_beg_time = 0.0;
  52. this->lidar.reset(new PointCloudXYZI());
  53. };
  54. double lidar_beg_time; // lidar data begin time in the MeasureGroup
  55. double lidar_end_time; // lidar data end time in the MeasureGroup
  56. PointCloudXYZI::Ptr lidar;
  57. deque<sensor_msgs::Imu::ConstPtr> imu;
  58. };
  59. struct StatesGroup
  60. {
  61. StatesGroup() {
  62. this->rot_end = M3D::Identity();
  63. this->pos_end = Zero3d;
  64. this->vel_end = Zero3d;
  65. this->bias_g = Zero3d;
  66. this->bias_a = Zero3d;
  67. this->gravity = Zero3d;
  68. this->cov = MD(DIM_STATE,DIM_STATE)::Identity() * INIT_COV;
  69. this->cov.block<9,9>(9,9) = MD(9,9)::Identity() * 0.00001;
  70. };
  71. StatesGroup(const StatesGroup& b) {
  72. this->rot_end = b.rot_end;
  73. this->pos_end = b.pos_end;
  74. this->vel_end = b.vel_end;
  75. this->bias_g = b.bias_g;
  76. this->bias_a = b.bias_a;
  77. this->gravity = b.gravity;
  78. this->cov = b.cov;
  79. };
  80. StatesGroup& operator=(const StatesGroup& b)
  81. {
  82. this->rot_end = b.rot_end;
  83. this->pos_end = b.pos_end;
  84. this->vel_end = b.vel_end;
  85. this->bias_g = b.bias_g;
  86. this->bias_a = b.bias_a;
  87. this->gravity = b.gravity;
  88. this->cov = b.cov;
  89. return *this;
  90. };
  91. StatesGroup operator+(const Matrix<double, DIM_STATE, 1> &state_add)
  92. {
  93. StatesGroup a;
  94. a.rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0));
  95. a.pos_end = this->pos_end + state_add.block<3,1>(3,0);
  96. a.vel_end = this->vel_end + state_add.block<3,1>(6,0);
  97. a.bias_g = this->bias_g + state_add.block<3,1>(9,0);
  98. a.bias_a = this->bias_a + state_add.block<3,1>(12,0);
  99. a.gravity = this->gravity + state_add.block<3,1>(15,0);
  100. a.cov = this->cov;
  101. return a;
  102. };
  103. StatesGroup& operator+=(const Matrix<double, DIM_STATE, 1> &state_add)
  104. {
  105. this->rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0));
  106. this->pos_end += state_add.block<3,1>(3,0);
  107. this->vel_end += state_add.block<3,1>(6,0);
  108. this->bias_g += state_add.block<3,1>(9,0);
  109. this->bias_a += state_add.block<3,1>(12,0);
  110. this->gravity += state_add.block<3,1>(15,0);
  111. return *this;
  112. };
  113. Matrix<double, DIM_STATE, 1> operator-(const StatesGroup& b)
  114. {
  115. Matrix<double, DIM_STATE, 1> a;
  116. M3D rotd(b.rot_end.transpose() * this->rot_end);
  117. a.block<3,1>(0,0) = Log(rotd);
  118. a.block<3,1>(3,0) = this->pos_end - b.pos_end;
  119. a.block<3,1>(6,0) = this->vel_end - b.vel_end;
  120. a.block<3,1>(9,0) = this->bias_g - b.bias_g;
  121. a.block<3,1>(12,0) = this->bias_a - b.bias_a;
  122. a.block<3,1>(15,0) = this->gravity - b.gravity;
  123. return a;
  124. };
  125. void resetpose()
  126. {
  127. this->rot_end = M3D::Identity();
  128. this->pos_end = Zero3d;
  129. this->vel_end = Zero3d;
  130. }
  131. M3D rot_end; // the estimated attitude (rotation matrix) at the end lidar point
  132. V3D pos_end; // the estimated position at the end lidar point (world frame)
  133. V3D vel_end; // the estimated velocity at the end lidar point (world frame)
  134. V3D bias_g; // gyroscope bias
  135. V3D bias_a; // accelerator bias
  136. V3D gravity; // the estimated gravity acceleration
  137. Matrix<double, DIM_STATE, DIM_STATE> cov; // states covariance
  138. };
  139. template<typename T>
  140. T rad2deg(T radians)
  141. {
  142. return radians * 180.0 / PI_M;
  143. }
  144. template<typename T>
  145. T deg2rad(T degrees)
  146. {
  147. return degrees * PI_M / 180.0;
  148. }
  149. template<typename T>
  150. auto set_pose6d(const double t, const Matrix<T, 3, 1> &a, const Matrix<T, 3, 1> &g, \
  151. const Matrix<T, 3, 1> &v, const Matrix<T, 3, 1> &p, const Matrix<T, 3, 3> &R)
  152. {
  153. Pose6D rot_kp;
  154. rot_kp.offset_time = t;
  155. for (int i = 0; i < 3; i++)
  156. {
  157. rot_kp.acc[i] = a(i);
  158. rot_kp.gyr[i] = g(i);
  159. rot_kp.vel[i] = v(i);
  160. rot_kp.pos[i] = p(i);
  161. for (int j = 0; j < 3; j++) rot_kp.rot[i*3+j] = R(i,j);
  162. }
  163. return move(rot_kp);
  164. }
  165. /* comment
  166. plane equation: Ax + By + Cz + D = 0
  167. convert to: A/D*x + B/D*y + C/D*z = -1
  168. solve: A0*x0 = b0
  169. where A0_i = [x_i, y_i, z_i], x0 = [A/D, B/D, C/D]^T, b0 = [-1, ..., -1]^T
  170. normvec: normalized x0
  171. */
  172. template<typename T>
  173. bool esti_normvector(Matrix<T, 3, 1> &normvec, const PointVector &point, const T &threshold, const int &point_num)
  174. {
  175. MatrixXf A(point_num, 3);
  176. MatrixXf b(point_num, 1);
  177. b.setOnes();
  178. b *= -1.0f;
  179. for (int j = 0; j < point_num; j++)
  180. {
  181. A(j,0) = point[j].x;
  182. A(j,1) = point[j].y;
  183. A(j,2) = point[j].z;
  184. }
  185. normvec = A.colPivHouseholderQr().solve(b);
  186. for (int j = 0; j < point_num; j++)
  187. {
  188. if (fabs(normvec(0) * point[j].x + normvec(1) * point[j].y + normvec(2) * point[j].z + 1.0f) > threshold)
  189. {
  190. return false;
  191. }
  192. }
  193. normvec.normalize();
  194. return true;
  195. }
  196. float calc_dist(PointType p1, PointType p2){
  197. float d = (p1.x - p2.x) * (p1.x - p2.x) + (p1.y - p2.y) * (p1.y - p2.y) + (p1.z - p2.z) * (p1.z - p2.z);
  198. return d;
  199. }
  200. template<typename T>
  201. bool esti_plane(Matrix<T, 4, 1> &pca_result, const PointVector &point, const T &threshold)
  202. {
  203. Matrix<T, NUM_MATCH_POINTS, 3> A;
  204. Matrix<T, NUM_MATCH_POINTS, 1> b;
  205. A.setZero();
  206. b.setOnes();
  207. b *= -1.0f;
  208. for (int j = 0; j < NUM_MATCH_POINTS; j++)
  209. {
  210. A(j,0) = point[j].x;
  211. A(j,1) = point[j].y;
  212. A(j,2) = point[j].z;
  213. }
  214. Matrix<T, 3, 1> normvec = A.colPivHouseholderQr().solve(b);
  215. T n = normvec.norm();
  216. pca_result(0) = normvec(0) / n;
  217. pca_result(1) = normvec(1) / n;
  218. pca_result(2) = normvec(2) / n;
  219. pca_result(3) = 1.0 / n;
  220. for (int j = 0; j < NUM_MATCH_POINTS; j++)
  221. {
  222. if (fabs(pca_result(0) * point[j].x + pca_result(1) * point[j].y + pca_result(2) * point[j].z + pca_result(3)) > threshold)
  223. {
  224. return false;
  225. }
  226. }
  227. return true;
  228. }
  229. #endif