lidar_calib_tools.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333
  1. /*
  2. * @Description: lidar calib tools
  3. * @Author: yct
  4. * @Date: 2021-09-02 11:02:00
  5. * @LastEditTime: 2022-01-25 12:15:07
  6. * @LastEditors: yct
  7. */
  8. #include "../tool/point_tool.h"
  9. #include <Eigen/Core>
  10. #include <Eigen/Geometry>
  11. /**
  12. * @description: used to find vlp16 intrinsic
  13. * @param {*}
  14. * @return {*}
  15. * @param {Quaterniond} ground_quat quaternion to align lidar coords with ground plane
  16. * @param {double} angle_z_axis rotation angle along z axis to align lidar coords with PLC coords
  17. */
  18. void find_intrinsic(Eigen::Vector3d ground_norm, Eigen::Vector3d y_axis)
  19. {
  20. Eigen::Quaterniond ground_quat = Eigen::Quaterniond::FromTwoVectors(ground_norm, Eigen::Vector3d::UnitZ());
  21. Eigen::Quaterniond xy_plane_quat = Eigen::Quaterniond::FromTwoVectors(y_axis, Eigen::Vector3d::UnitY());
  22. // std::cout << "y euler: " << xy_plane_quat.toRotationMatrix().eulerAngles(2, 1, 0).transpose() << std::endl;
  23. Eigen::Matrix3d combined_rotation = ground_quat.toRotationMatrix() * xy_plane_quat.toRotationMatrix();
  24. Eigen::Vector3d euler_angles = combined_rotation.eulerAngles(2, 1, 0);
  25. for (size_t i = 0; i < euler_angles.rows(); i++)
  26. {
  27. if(fabs(euler_angles[i]) > M_PI_2)
  28. {
  29. if(euler_angles[i] > 0)
  30. {
  31. euler_angles[i] = euler_angles[i] - M_PI;
  32. }else{
  33. euler_angles[i] = M_PI + euler_angles[i];
  34. }
  35. }
  36. }
  37. if(euler_angles[0]<0)
  38. {
  39. euler_angles[0] = euler_angles[0] + M_PI;
  40. }
  41. std::cout << "lidar intrinsic y p r: " << euler_angles.transpose()*180.0/M_PI << std::endl;
  42. }
  43. /**
  44. * @description: fit ground norm from two poles, then find y axis direction from front to back
  45. * @return {*}
  46. * @param {Ptr} front_barrier
  47. * @param {Ptr} back_barrier
  48. */
  49. void find_rotation_from_points(pcl::PointCloud<pcl::PointXYZ>::Ptr front_barrier, pcl::PointCloud<pcl::PointXYZ>::Ptr back_barrier,
  50. Eigen::Vector3d &front_direction, Eigen::Vector3d &back_direction, Eigen::Vector3d &y_direction)
  51. {
  52. pcl::PointCloud<pcl::PointXYZ>::Ptr direction_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  53. Eigen::Vector3d point_front, point_back;
  54. // 根据点云拟合直线
  55. //创建一个模型参数对象,用于记录拟合结果
  56. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  57. //inliers通过点云序号来记录模型内点
  58. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  59. //创建一个分割对象
  60. pcl::SACSegmentation<pcl::PointXYZ> seg;
  61. //Optional,设置结果直线展示的点是分割掉的点还是分割剩下的点
  62. seg.setOptimizeCoefficients(true);//flase 展示的是分割剩下的点
  63. //Mandatory-设置目标几何形状
  64. seg.setModelType(pcl::SACMODEL_LINE);
  65. //分割方法:随机采样法
  66. seg.setMethodType(pcl::SAC_RANSAC);
  67. //设置误差容忍范围,也就是阈值
  68. seg.setDistanceThreshold(0.01);
  69. //输入点云
  70. seg.setInputCloud(front_barrier);
  71. //分割点云
  72. seg.segment(*inliers, *coefficients);
  73. if(coefficients->values.size() < 6)
  74. {
  75. std::cout << "fatal, front line coeff size not enough." << std::endl;
  76. return;
  77. }
  78. else
  79. {
  80. point_front << coefficients->values[0], coefficients->values[1], coefficients->values[2];
  81. front_direction << coefficients->values[3], coefficients->values[4], coefficients->values[5];
  82. std::cout << "front direction: " << front_direction.transpose() << std::endl;
  83. }
  84. // 保存前杆方向点云,调试用
  85. for (size_t i = 0; i < 200; i++)
  86. {
  87. Eigen::Vector3d t_point = point_front + front_direction * 0.01 * i;
  88. direction_cloud->push_back(pcl::PointXYZ(t_point.x(), t_point.y(), t_point.z()));
  89. }
  90. seg.setInputCloud(back_barrier);
  91. seg.segment(*inliers, *coefficients);
  92. if(coefficients->values.size() < 6)
  93. {
  94. std::cout << "fatal, back line coeff size not enough." << std::endl;
  95. return;
  96. }
  97. else
  98. {
  99. point_back << coefficients->values[0], coefficients->values[1], coefficients->values[2];
  100. back_direction << coefficients->values[3], coefficients->values[4], coefficients->values[5];
  101. std::cout << "back direction: " << back_direction.transpose() << std::endl;
  102. }
  103. // 保存后杆方向点云,调试用
  104. for (size_t i = 0; i < 200; i++)
  105. {
  106. Eigen::Vector3d t_point = point_back + back_direction * 0.01 * i;
  107. direction_cloud->push_back(pcl::PointXYZ(t_point.x(), t_point.y(), t_point.z()));
  108. }
  109. std::cout << "point front to back : " << point_front.transpose() << " -----> " << point_back.transpose() << std::endl;
  110. // 注意y方向需要清除z分量
  111. y_direction = point_front - point_back;
  112. y_direction.z() = 0.0;
  113. std::cout << "y direction: " << y_direction.transpose() << std::endl;
  114. // 保存y方向点云,调试用
  115. for (size_t i = 0; i < 200; i++)
  116. {
  117. Eigen::Vector3d t_point = point_back + y_direction * 0.01 * i;
  118. direction_cloud->push_back(pcl::PointXYZ(t_point.x(), t_point.y(), t_point.z()));
  119. }
  120. save_cloud_txt(direction_cloud, "./direction_cloud.txt");
  121. }
  122. // passthrough and fit plane
  123. #include "pcl/filters/passthrough.h"
  124. void find_ground(pcl::PointCloud<pcl::PointXYZ>::Ptr ground_cloud, Eigen::Vector4d &params, double avg_z=0.03)
  125. {
  126. if(ground_cloud->size()<=0)
  127. {
  128. std::cout<<"empty ground cloud"<<std::endl;
  129. return;
  130. }
  131. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  132. // 直通滤波
  133. double min_x = -2.6, max_x = 2.3, min_y = -3.0, max_y = 3.0, max_z = 0.1;
  134. for (size_t i = 0; i < ground_cloud->size(); i++)
  135. {
  136. pcl::PointXYZ pt = ground_cloud->points[i];
  137. if (pt.x > min_x && pt.x < max_x && pt.y > min_y && pt.y < max_y && pt.z < max_z)
  138. {
  139. t_cloud->push_back(pt);
  140. }
  141. }
  142. // 平面拟合
  143. if(t_cloud->size()<1)
  144. {
  145. std::cout<<"ground cloud not enough"<<std::endl;
  146. return;
  147. }
  148. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  149. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  150. pcl::SACSegmentation<pcl::PointXYZ> seg;
  151. seg.setOptimizeCoefficients(true);
  152. seg.setModelType(pcl::SACMODEL_PLANE);
  153. seg.setMethodType(pcl::SAC_RANSAC);
  154. seg.setDistanceThreshold(avg_z);
  155. seg.setInputCloud(t_cloud);
  156. seg.segment(*inliers, *coefficients);
  157. if(coefficients->values.size()<4)
  158. {
  159. std::cout<<"fit plane coeff size not enough"<<std::endl;
  160. return;
  161. }
  162. params << coefficients->values[0], coefficients->values[1], coefficients->values[2], coefficients->values[3];
  163. }
  164. void matrix_trans()
  165. {
  166. // 921 A left
  167. Eigen::Matrix3d rot_matrix0;
  168. rot_matrix0.setIdentity();
  169. // rot_matrix0 << 0.3967, -0.9023, -0.1686,
  170. // -0.8619, -0.4293, 0.2698,
  171. // -0.3159, 0.03827, -0.948;
  172. // 671 B left
  173. // rot_matrix0 << 0.095394842327, -0.995411992073, 0.007405274082,
  174. // -0.901792705059, -0.083268046379, 0.42407116293,
  175. // -0.421508878469, -0.047132223845, -0.9055985808;
  176. // 211 B out left
  177. // rot_matrix0 << 0.083884611726, 0.990452945232, -0.109390966594,
  178. // 0.894117712975, -0.123275801539, -0.430530607700,
  179. // -0.439905554056, -0.061693508178, -0.89592242240;
  180. // 541
  181. // rot_matrix0 << 0.127279058099, -0.989588797092, -0.067186594009,
  182. // -0.888444364071, -0.143861815333, 0.435855954885,
  183. // -0.440983742476, 0.004216216505, -0.897505164146;
  184. //621
  185. rot_matrix0 << -0.108142159879, -0.990688860416, 0.082709200680, 3.672443628311,
  186. 0.993864834309, -0.109678961337, -0.014255203307, -0.117867439985,
  187. 0.023193931207, 0.080660179257, 0.996471762657, 0.054298080504,
  188. 0.000000000000, 0.000000000000, 0.000000000000, 1.000000000000;
  189. Eigen::Matrix3d rot_matrix1;
  190. rot_matrix1.setIdentity();
  191. // rot_matrix1 << 0.9993, 0.03618, 0.0,
  192. // -0.03618, 0.9993, 0.0,
  193. // 0.0, 0.0, 1.0;
  194. Eigen::Vector3d euler = (rot_matrix1 * rot_matrix0).eulerAngles(2, 1, 0);
  195. std::cout << "mat to euler left (z y x): " << euler[0]*180.0/M_PI << ", " << euler[1]*180.0/M_PI << ", " << euler[2]*180.0/M_PI << std::endl;
  196. // 541 A right
  197. Eigen::Matrix3d rot_matrix2;
  198. rot_matrix2.setIdentity();
  199. // rot_matrix2 << 0.0812, 0.997, 0.0185,
  200. // 0.8787, -0.0628, -0.4731,
  201. // -0.4703, 0.0547, -0.8808;
  202. // 091 B right
  203. // rot_matrix2 << -0.089172042906, -0.994127452374, 0.06131035462,
  204. // -0.912935018539, 0.106191061437, 0.394047111273,
  205. // -0.398243665695, -0.020834382623, -0.9170430302;
  206. // 051 B out right
  207. // rot_matrix2 << -0.097560293972, 0.995089590549, 0.016694894060,
  208. // 0.888557076454, 0.094646930695, -0.448896795511,
  209. // -0.448272645473, -0.028960136697, -0.89342767000;
  210. // 001
  211. // rot_matrix2 << -0.077520310879, -0.990943193436, 0.109645560384,
  212. // -0.916525423527, 0.114115700126, 0.383352011442,
  213. // -0.392392337322, -0.070775382221, -0.91707092523;
  214. //131
  215. rot_matrix2 << 0.144158020616, 0.987975895405, -0.055875182152,
  216. 0.896719515324, -0.154303416610, -0.414830744267,
  217. -0.418464511633, 0.009696813300, -0.908181369305;
  218. Eigen::Matrix3d rot_matrix3;
  219. rot_matrix3.setIdentity();
  220. // rot_matrix3 << 0.97486, 0.2228, 0.0,
  221. // -0.2228, 0.97486, 0.0,
  222. // 0.0, 0.0, 1.0;
  223. euler = (rot_matrix3 * rot_matrix2).eulerAngles(2, 1, 0);
  224. std::cout << "mat to euler right (z y x): " << euler[0]*180.0/M_PI << ", " << euler[1]*180.0/M_PI << ", " << euler[2]*180.0/M_PI << std::endl;
  225. //541: 98.1528, 153.833, -0.269157
  226. //001: 85.1654, 156.897, 4.41308
  227. // 921----- -2.31 161.58 -64 2.512
  228. // 541----- 176.45 28.05 71.85
  229. euler << -2.31, 161.58, -64;
  230. Eigen::Matrix3d euler2mat = Eigen::AngleAxisd(euler[2]*M_PI/180.0, Eigen::Vector3d::UnitZ()).toRotationMatrix() *
  231. Eigen::AngleAxisd(euler[1]*M_PI/180.0, Eigen::Vector3d::UnitY()).toRotationMatrix() *
  232. Eigen::AngleAxisd(euler[0]*M_PI/180.0, Eigen::Vector3d::UnitX()).toRotationMatrix();
  233. std::cout << "921 euler mat: \n" << euler2mat << std::endl;
  234. // -0.415912 0.892481 0.174631
  235. // 0.852745 0.449462 -0.266101
  236. // -0.31598 0.0382411 -0.947995
  237. euler << 176.45, 28.05, 71.85;
  238. euler2mat = Eigen::AngleAxisd(euler[2]*M_PI/180.0, Eigen::Vector3d::UnitZ()).toRotationMatrix() *
  239. Eigen::AngleAxisd(euler[1]*M_PI/180.0, Eigen::Vector3d::UnitY()).toRotationMatrix() *
  240. Eigen::AngleAxisd(euler[0]*M_PI/180.0, Eigen::Vector3d::UnitX()).toRotationMatrix();
  241. std::cout << "541 euler mat: \n" << euler2mat << std::endl;
  242. // 0.274916 0.957491 -0.0873633
  243. // 0.838626 -0.28324 -0.465276
  244. // -0.470242 0.0546463 -0.880844
  245. }
  246. int main()
  247. {
  248. matrix_trans();
  249. return 0;
  250. // calib process:
  251. // 1. cc cut and fit ground, get normal and z
  252. // 2. get front and back pole txt
  253. // 3. run this calib func to get rpy and z
  254. std::cout << "------------------------ start calib lidar 0 ----------------------" << std::endl;
  255. // lidar 0 normal [09:22:54] - normal: (-0.000392,-0.011935,0.999929) z -0.07697
  256. // 90.6538 0.68354 0.0302616
  257. // lidar 1 normal 0.000297,-0.001893,0.999998 z -0.0686
  258. // 91.3879 0.108841 -0.0143847
  259. // lidar 2 normal [10:43:07] - normal: (0.001131,-0.024040,0.999710) z -0.0461051
  260. // 86.3796 1.37069 -0.15165
  261. // lidar 3 normal [11:18:44] - normal: (0.000833,0.010742,0.999942) z -0.071
  262. // 91.4077 -0.614125 -0.0628335
  263. // pitch 1.1 ---- 0.485875
  264. pcl::PointCloud<pcl::PointXYZ>::Ptr t_front, t_back;
  265. t_front = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  266. t_back = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  267. if (!read_pointcloud("/home/zx/yct/chutian_measure_2021/setting/calib/3front_pole.txt", t_front))
  268. {
  269. std::cout << "read front failed." << std::endl;
  270. return -1;
  271. }
  272. if(!read_pointcloud("/home/zx/yct/chutian_measure_2021/setting/calib/3back_pole.txt", t_back))
  273. {
  274. std::cout << "read back failed." << std::endl;
  275. return -1;
  276. }
  277. Eigen::Vector3d front_direction, back_direction, y_direction;
  278. find_rotation_from_points(t_front, t_back, front_direction, back_direction, y_direction);
  279. // 经过测试,地面法向量不适宜使用杆子获取,还是使用地面环点云拟合获得
  280. // find_intrinsic((front_direction + back_direction) / 2.0, y_direction);
  281. // find_intrinsic(Eigen::Vector3d(-0.000392,-0.011935,0.999929), y_direction);
  282. // find_intrinsic(Eigen::Vector3d(0.001131,-0.024040,0.999710), y_direction);
  283. find_intrinsic(Eigen::Vector3d(0.000833,0.010742,0.999942), y_direction);
  284. return 0;
  285. std::cout << "------------------------ start calib lidar 1 ----------------------" << std::endl;
  286. // cloud 1
  287. if (!read_pointcloud("/home/youchen/extra_space/chutian/fence_wj/front_pole2.txt", t_front))
  288. {
  289. std::cout << "read front failed." << std::endl;
  290. return -1;
  291. }
  292. if(!read_pointcloud("/home/youchen/extra_space/chutian/fence_wj/back_pole2.txt", t_back))
  293. {
  294. std::cout << "read back failed." << std::endl;
  295. return -1;
  296. }
  297. find_rotation_from_points(t_front, t_back, front_direction, back_direction, y_direction);
  298. // -0.00566995 0-0.0233422 0000.999712 000.0949598
  299. find_intrinsic(Eigen::Vector3d(-0.00566995,-0.0233422,0.999712), y_direction);
  300. return 0;
  301. }