rotate_center_caliber.cpp 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280
  1. //
  2. // Created by zx on 2021/8/27.
  3. //
  4. #include "rotate_center_caliber.h"
  5. #include <pcl/registration/ndt.h>
  6. #include <pcl/visualization/pcl_visualizer.h>
  7. // extern pcl::visualization::PCLVisualizer viewer;
  8. // extern std::mutex mut;
  9. void rotate_center_caliber::rotate_center_caliber_init()
  10. {
  11. }
  12. void rotate_center_caliber::rotate_center_caliber_uninit()
  13. {
  14. delete mp_matcher;
  15. mp_matcher = nullptr;
  16. }
  17. void rotate_center_caliber::set_first_frame(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_model)
  18. {
  19. m_model_cloud=cloud_model;
  20. Eigen::Vector4f centroid;
  21. pcl::compute3DCentroid(*cloud_model, centroid);
  22. m_center.x=centroid[0];
  23. m_center.y=centroid[1];
  24. m_center.z=centroid[2];
  25. //平移点云
  26. Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity();
  27. pcl::PointCloud<pcl::PointXYZ>::Ptr transformed_cloud(new pcl::PointCloud<pcl::PointXYZ>());
  28. transform_2.translation() << -centroid[0],-centroid[1],-centroid[2];
  29. pcl::transformPointCloud(*cloud_model, *transformed_cloud, transform_2);
  30. printf("model center: %.5f,%.5f,%.5f\n",centroid[0],centroid[1],centroid[2]);
  31. mp_matcher=new detect_ceres3d(transformed_cloud);
  32. }
  33. bool rotate_center_caliber::push_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  34. {
  35. //平移点云
  36. Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity();
  37. pcl::PointCloud<pcl::PointXYZ>::Ptr offset_cloud(new pcl::PointCloud<pcl::PointXYZ>());
  38. transform_2.translation() << -m_center.x,-m_center.y,-m_center.z;
  39. pcl::transformPointCloud(*cloud, *offset_cloud, transform_2);
  40. // mut.lock();
  41. // pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color(cloud, 0, 255, 0); // green
  42. // viewer.removePointCloud("cloud_rotation");
  43. // viewer.addPointCloud(cloud, single_color,"cloud_rotation");
  44. // mut.unlock();
  45. if(mp_matcher== nullptr)
  46. return false;
  47. static detect_ceres3d::Detect_result last_result;
  48. std::string error;
  49. pcl::PointCloud<pcl::PointXYZ>::Ptr transform_cloud(new pcl::PointCloud<pcl::PointXYZ>());
  50. detect_ceres3d::Detect_result result=last_result;
  51. if(mp_matcher->detect(offset_cloud,result,transform_cloud,error))
  52. {
  53. if(fabs(result.theta-last_result.theta)>1.0/180.*M_PI)
  54. {
  55. printf(" detect success r : %.3f t:%.5f,%.5f\n", result.theta * 180. / M_PI, result.cx, result.cy);
  56. Eigen::Affine3f transform_affine = Eigen::Affine3f::Identity();
  57. pcl::PointCloud<pcl::PointXYZ>::Ptr new_cloud(new pcl::PointCloud<pcl::PointXYZ>());
  58. transform_affine.translation() << m_center.x, m_center.y, m_center.z;
  59. pcl::transformPointCloud(*transform_cloud, *new_cloud, transform_affine);
  60. // mut.lock();
  61. // pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color(cloud, 255, 0, 0); // green
  62. // viewer.removePointCloud("ndt_cloud");
  63. // viewer.addPointCloud(new_cloud, single_color, "ndt_cloud");
  64. // mut.unlock();
  65. match_transform solve_data;
  66. solve_data.theta = result.theta;
  67. solve_data.dx = result.cx;
  68. solve_data.dy = result.cy;
  69. m_match_datas.push_back(solve_data);
  70. last_result = result;
  71. }
  72. else
  73. {
  74. // std::cout << " small dtheta: " << (result.theta - last_result.theta) * 180.0 / M_PI << std::endl;
  75. }
  76. }else{
  77. std::cout << "?????" << std::endl;
  78. }
  79. /*Eigen::Matrix<float,6,1> temp;
  80. temp.setZero();
  81. static Eigen::Matrix<float, 6,1> last_transform=temp;
  82. printf("init r:%.3f,%.3f,%.3f, t :%.5f,%.5f,%.5f\n",
  83. last_transform(2,0)*180.0/M_PI,last_transform(1,0)*180.0/M_PI,last_transform(0,0)*180.0/M_PI,
  84. last_transform(3,0),last_transform(4,0),last_transform(5,0));
  85. Eigen::Matrix4f matrix=match(m_model_cloud,cloud,last_transform);
  86. //std::cout<<" match :"<<matrix<<std::endl;
  87. Eigen::Matrix3f roation=matrix.topLeftCorner(3,3);
  88. Eigen::Vector3f euler_angles = roation.eulerAngles(0, 1, 2);
  89. //std::cout<<euler_angles<<std::endl;
  90. printf("r:%.3f,%.3f,%.3f t:%.5f,%.5f\n",euler_angles[2]*180.0/M_PI,euler_angles[1]*180.0/M_PI,
  91. euler_angles[0]*180.0/M_PI,matrix(0,3),matrix(1,3));
  92. match_transform solve_data;
  93. solve_data.theta=euler_angles[2];
  94. solve_data.dx=matrix(0,3);
  95. solve_data.dy=matrix(1,3);
  96. m_match_datas.push_back(solve_data);
  97. last_transform[0]=euler_angles[0];
  98. last_transform[1]=euler_angles[1];
  99. last_transform[2]=euler_angles[2];
  100. last_transform[3]=matrix(0,3);
  101. last_transform[4]=matrix(1,3);
  102. last_transform[5]=matrix(2,3);
  103. */
  104. if(solve())
  105. {
  106. /*printf(" solve center = %.5f,%.5f\n",
  107. m_rotation_center_x,m_rotation_center_y);*/
  108. // updata_points();
  109. }
  110. }
  111. Eigen::Matrix4f rotate_center_caliber::match(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_center,
  112. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,Eigen::Matrix<float, 6,1> init_transform)
  113. {
  114. //初始化正态分布变换(NDT)
  115. pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;
  116. //设置依赖尺度NDT参数
  117. //为终止条件设置最小转换差异
  118. ndt.setTransformationEpsilon(0.0001);
  119. //为More-Thuente线搜索设置最大步长
  120. ndt.setStepSize(0.1);
  121. //设置NDT网格结构的分辨率(VoxelGridCovariance)
  122. ndt.setResolution(0.3);
  123. //设置匹配迭代的最大次数
  124. ndt.setMaximumIterations(100);
  125. // 设置要配准的点云
  126. ndt.setInputCloud(cloud);
  127. //设置点云配准目标
  128. ndt.setInputTarget(cloud_center);
  129. //设置使用机器人测距法得到的初始对准估计结果
  130. Eigen::AngleAxisf rollAngle(Eigen::AngleAxisf(init_transform(0), Eigen::Vector3f::UnitX()));
  131. Eigen::AngleAxisf pitchAngle(Eigen::AngleAxisf(init_transform(1), Eigen::Vector3f::UnitY()));
  132. Eigen::AngleAxisf yawAngle(Eigen::AngleAxisf(init_transform(2), Eigen::Vector3f::UnitZ()));
  133. Eigen::AngleAxisf rotation ;
  134. rotation = yawAngle*pitchAngle*rollAngle;
  135. Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity();
  136. transform_2.translation() << init_transform(3),init_transform(4),init_transform(5); // 三个数分别对应X轴、Y轴、Z轴方向上的平移
  137. transform_2.rotate(rotation); //同理,UnitX(),绕X轴;UnitY(
  138. Eigen::Matrix4f init_guess = transform_2.matrix();
  139. //计算需要的刚体变换以便将输入的点云匹配到目标点云
  140. pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  141. ndt.align(*output_cloud, init_guess);
  142. std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged()
  143. << " score: " << ndt.getFitnessScore() << std::endl;
  144. //使用创建的变换对未过滤的输入点云进行变换
  145. return ndt.getFinalTransformation();
  146. }
  147. bool rotate_center_caliber::solve()
  148. {
  149. int size=m_match_datas.size();
  150. if(size<=1)
  151. {
  152. LOG(INFO) <<"match_data size:"<< m_match_datas.size();
  153. return false;
  154. }
  155. Eigen::MatrixXf A;
  156. A.resize(2*size,2);
  157. Eigen::MatrixXf B;
  158. B.resize(2*size,1);
  159. for(int i=0;i<size;i++)
  160. {
  161. match_transform data=m_match_datas[i];
  162. float da=-data.theta;
  163. float dx=-data.dx;
  164. float dy=-data.dy;
  165. float RA=1-cos(da);
  166. float RB=sin(da);
  167. float RC=-sin(da);
  168. float RD=1-cos(da);
  169. A(i*2+0,0)=RA;
  170. A(i*2+0,1)=RB;
  171. A(i*2+1,0)=RC;
  172. A(i*2+1,1)=RD;
  173. B(i*2+0,0)=dx;
  174. B(i*2+1,0)=dy;
  175. }
  176. //std::cout<<"A:"<<A<<std::endl;
  177. Eigen::MatrixXf result= (A.transpose()*A).inverse()*(A.transpose())*B;
  178. //std::cout<<"result M:"<<result.transpose()<<std::endl;
  179. m_rotation_center_x=result(0,0)+m_center.x;
  180. m_rotation_center_y=result(1,0)+m_center.y;
  181. return true;
  182. }
  183. void rotate_center_caliber::updata_points()
  184. {
  185. if(m_match_datas.size()<1)
  186. return ;
  187. static int id = 0;
  188. if(id==0)
  189. {
  190. // viewer.addLine(pcl::PointXYZ(m_center.x,m_center.y,0),
  191. // pcl::PointXYZ(m_rotation_center_x,m_rotation_center_y,0),0,1,1,"org");
  192. }
  193. double max_d=-1,min_d=1e9;
  194. for (int i = 0; i < m_match_datas.size(); ++i)
  195. {
  196. float x = -m_match_datas[i].dx + m_center.x;
  197. float y = -m_match_datas[i].dy + m_center.y;
  198. char buf[32] = {0};
  199. sprintf(buf, "line_%d", i);
  200. // mut.lock();
  201. // if (i < id)
  202. // {
  203. // viewer.removeShape(buf);
  204. // }
  205. // viewer.addLine(pcl::PointXYZ(x, y, 0),
  206. // pcl::PointXYZ(m_rotation_center_x, m_rotation_center_y, 0),
  207. // 0,
  208. // 0,
  209. // 1,
  210. // buf);
  211. // mut.unlock();
  212. double distance=sqrt(pow(m_rotation_center_x-x,2)+pow(m_rotation_center_y-y,2));
  213. if(distance<min_d)
  214. min_d=distance;
  215. if(distance>max_d)
  216. max_d=distance;
  217. }
  218. id = m_match_datas.size();
  219. if((max_d-min_d)>0.01)
  220. {
  221. LOG(ERROR)<<" distances verify failed ";
  222. return ;
  223. }
  224. LOG(INFO)<<" distances verify :"<<max_d-min_d;
  225. }