point_tool.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337
  1. //
  2. // Created by zx on 2021/5/11.
  3. //
  4. #include "point_tool.h"
  5. void rotation_matrix_to_rpy()
  6. {
  7. //2# 92.0084 112.664 179.263
  8. //3# 85.2597 73.8993 -1.70915
  9. //4# 91.93 112.146 -179.65
  10. //5# 32.9435 67.8446 -52.9897
  11. //6# 124.098 119.42 -150.147
  12. //8# 37.3443 111.887 130.948
  13. /*
  14. mat_r00:0.0229183
  15. mat_r01:-0.9985044
  16. mat_r02:0.0496393
  17. mat_r03:5287.829
  18. mat_r10:0.2763783
  19. mat_r11:0.0540452
  20. mat_r12:0.9595283
  21. mat_r13:-2399.535
  22. mat_r20:-0.9607757
  23. mat_r21:-0.0082715
  24. mat_r22:0.2772034
  25. mat_r23:6674.29500*/
  26. Eigen::Matrix3d mat;
  27. mat<<0.0229183,
  28. -0.9985044,
  29. 0.0496393,
  30. 0.2763783,
  31. 0.0540452,
  32. 0.9595283,
  33. -0.9607757,
  34. -0.0082715,
  35. 0.2772034;
  36. Eigen::Vector3d euler_angles = mat.eulerAngles(2, 1, 0);
  37. std::cout<<euler_angles*180.0/M_PI<<std::endl;
  38. }
  39. void rpy_to_rotation_matrix()
  40. {
  41. //
  42. float ea[3]={-172,105.42,99.38};
  43. Eigen::Matrix3d rotation_matrix3;
  44. rotation_matrix3 = Eigen::AngleAxisd(ea[2]*M_PI/180.0, Eigen::Vector3d::UnitZ()) *
  45. Eigen::AngleAxisd(ea[1]*M_PI/180.0, Eigen::Vector3d::UnitY()) *
  46. Eigen::AngleAxisd(ea[0]*M_PI/180.0, Eigen::Vector3d::UnitX());
  47. std::cout << "rotation matrix3 =\n" << rotation_matrix3 << std::endl;
  48. }
  49. void reverse_test(){
  50. Eigen::Matrix3d mat;
  51. mat<<-0.2963634,0.9547403,-0.0252988,-0.2261306,-0.0958803,-0.9693665,-0.9279189,-0.2815638,0.2443113;
  52. Eigen::Vector3d euler_angles = mat.eulerAngles(2, 1, 0);
  53. std::cout<<euler_angles*180.0/M_PI<<std::endl;
  54. Eigen::Matrix3d rotation_matrix3;
  55. rotation_matrix3 = Eigen::AngleAxisd(euler_angles[0], Eigen::Vector3d::UnitZ()) *
  56. Eigen::AngleAxisd(euler_angles[1], Eigen::Vector3d::UnitY()) *
  57. Eigen::AngleAxisd(euler_angles[2], Eigen::Vector3d::UnitX());
  58. std::cout << "origin matrix3 =\n" << mat << std::endl;
  59. std::cout << "rotation matrix3 =\n" << rotation_matrix3 << std::endl;
  60. }
  61. bool string2point(std::string str,pcl::PointXYZ& point)
  62. {
  63. std::istringstream iss;
  64. iss.str(str);
  65. float value;
  66. float data[3]={0};
  67. for(int i=0;i<3;++i)
  68. {
  69. if(iss>>value)
  70. {
  71. data[i]=value;
  72. }
  73. else
  74. {
  75. return false;
  76. }
  77. }
  78. point.x=data[0];
  79. point.y=data[1];
  80. point.z=data[2];
  81. return true;
  82. }
  83. pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
  84. {
  85. std::ifstream fin(file.c_str());
  86. const int line_length=64;
  87. char str[line_length]={0};
  88. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  89. while(fin.getline(str,line_length))
  90. {
  91. pcl::PointXYZ point;
  92. if(string2point(str,point))
  93. {
  94. cloud->push_back(point);
  95. }
  96. }
  97. return cloud;
  98. }
  99. void save_cloud_txt(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string file)
  100. {
  101. FILE* pf=fopen(file.c_str(),"w");
  102. for(int i=0;i<cloud->size();++i)
  103. {
  104. pcl::PointXYZ point=cloud->points[i];
  105. fprintf(pf,"%.3f %.3f %.3f\n",point.x,point.y,point.z);
  106. }
  107. fclose(pf);
  108. }
  109. void save_cloud_txt(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,std::string file)
  110. {
  111. FILE* pf=fopen(file.c_str(),"w");
  112. for(int i=0;i<cloud->size();++i)
  113. {
  114. pcl::PointXYZRGB point=cloud->points[i];
  115. fprintf(pf,"%.3f %.3f %.3f %d %d %d\n",point.x,point.y,point.z,point.r,point.g,point.b);
  116. }
  117. fclose(pf);
  118. }
  119. //欧式聚类*******************************************************
  120. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  121. {
  122. std::vector<pcl::PointIndices> ece_inlier;
  123. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  124. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  125. ece.setInputCloud(sor_cloud);
  126. ece.setClusterTolerance(0.2);
  127. ece.setMinClusterSize(20);
  128. ece.setMaxClusterSize(20000);
  129. ece.setSearchMethod(tree);
  130. ece.extract(ece_inlier);
  131. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  132. for (int i = 0; i < ece_inlier.size(); i++)
  133. {
  134. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  135. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  136. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy);//按照索引提取点云数据
  137. segmentation_clouds.push_back(cloud_copy);
  138. }
  139. return segmentation_clouds;
  140. }
  141. double distance(cv::Point2f p1, cv::Point2f p2)
  142. {
  143. return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  144. }
  145. bool isRect(std::vector<cv::Point2f>& points)
  146. {
  147. if (points.size() == 4)
  148. {
  149. double L[3] = {0.0};
  150. L[0] = distance(points[0], points[1]);
  151. L[1] = distance(points[1], points[2]);
  152. L[2] = distance(points[0], points[2]);
  153. double max_l = L[0];
  154. double l1 = L[1];
  155. double l2 = L[2];
  156. cv::Point2f ps = points[0], pt = points[1];
  157. cv::Point2f pc = points[2];
  158. for (int i = 1; i < 3; ++i) {
  159. if (L[i] > max_l)
  160. {
  161. max_l = L[i];
  162. l1 = L[abs(i + 1) % 3];
  163. l2 = L[abs(i + 2) % 3];
  164. ps = points[i % 3];
  165. pt = points[(i + 1) % 3];
  166. pc = points[(i + 2) % 3];
  167. }
  168. }
  169. //直角边与坐标轴的夹角 <20°
  170. float thresh=20.0*M_PI/180.0;
  171. cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
  172. float angle=atan2(vct.y,vct.x);
  173. if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
  174. {
  175. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  176. return false;
  177. }
  178. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  179. if (fabs(cosa) >= 0.15) {
  180. /*char description[255]={0};
  181. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  182. std::cout<<description<<std::endl;*/
  183. return false;
  184. }
  185. float width=std::min(l1,l2);
  186. float length=std::max(l1,l2);
  187. if(width<1.400 || width >1.900 || length >3.300 ||length < 2.200)
  188. {
  189. /*char description[255]={0};
  190. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  191. std::cout<<description<<std::endl;*/
  192. return false;
  193. }
  194. double d = distance(pc, points[3]);
  195. cv::Point2f center1 = (ps + pt) * 0.5;
  196. cv::Point2f center2 = (pc + points[3]) * 0.5;
  197. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150) {
  198. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  199. char description[255]={0};
  200. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  201. std::cout<<description<<std::endl;*/
  202. return false;
  203. }
  204. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  205. return true;
  206. }
  207. else if(points.size()==3)
  208. {
  209. double L[3] = {0.0};
  210. L[0] = distance(points[0], points[1]);
  211. L[1] = distance(points[1], points[2]);
  212. L[2] = distance(points[0], points[2]);
  213. double max_l = L[0];
  214. double l1 = L[1];
  215. double l2 = L[2];
  216. int max_index = 0;
  217. cv::Point2f ps = points[0], pt = points[1];
  218. cv::Point2f pc = points[2];
  219. for (int i = 1; i < 3; ++i) {
  220. if (L[i] > max_l) {
  221. max_index = i;
  222. max_l = L[i];
  223. l1 = L[abs(i + 1) % 3];
  224. l2 = L[abs(i + 2) % 3];
  225. ps = points[i % 3];
  226. pt = points[(i + 1) % 3];
  227. pc = points[(i + 2) % 3];
  228. }
  229. }
  230. //直角边与坐标轴的夹角 <20°
  231. float thresh=20.0*M_PI/180.0;
  232. cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
  233. float angle=atan2(vct.y,vct.x);
  234. if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
  235. {
  236. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  237. return false;
  238. }
  239. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  240. if (fabs(cosa) >= 0.15) {
  241. /*char description[255]={0};
  242. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  243. std::cout<<description<<std::endl;*/
  244. return false;
  245. }
  246. double l=std::max(l1,l2);
  247. double w=std::min(l1,l2);
  248. if(l>2.100 && l<3.300 && w>1.400 && w<2.100)
  249. {
  250. //生成第四个点
  251. cv::Point2f vec1=ps-pc;
  252. cv::Point2f vec2=pt-pc;
  253. cv::Point2f point4=(vec1+vec2)+pc;
  254. points.push_back(point4);
  255. /*char description[255]={0};
  256. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  257. std::cout<<description<<std::endl;*/
  258. return true;
  259. }
  260. else
  261. {
  262. /*char description[255]={0};
  263. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  264. std::cout<<description<<std::endl;*/
  265. return false;
  266. }
  267. }
  268. //std::cout<<" default false"<<std::endl;
  269. return false;
  270. }
  271. bool read_pointcloud(std::string filename, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud)
  272. {
  273. // std::lock_guard<std::mutex> lck(m_cloud_mutex);
  274. pointcloud->clear();
  275. std::ifstream in(filename);
  276. if (!in.is_open())
  277. {
  278. std::cout << "failed to open file " << filename << std::endl;
  279. return false;
  280. }
  281. while (!in.eof())
  282. {
  283. std::string t_linestr;
  284. if (getline(in, t_linestr))
  285. {
  286. std::vector<std::string> str_vector;
  287. std::stringstream ss(t_linestr);
  288. std::string num_str;
  289. while (getline(ss, num_str, ' '))
  290. {
  291. str_vector.push_back(num_str);
  292. }
  293. if (str_vector.size() != 3)
  294. {
  295. std::cout << "unsupported point cloud / cannot find point x y z value: " << filename << std::endl;
  296. return false;
  297. }
  298. pcl::PointXYZ t_cloud;
  299. t_cloud.x = stod(str_vector[0]);
  300. t_cloud.y = stod(str_vector[1]);
  301. t_cloud.z = stod(str_vector[2]);
  302. pointcloud->push_back(t_cloud);
  303. }
  304. }
  305. in.close();
  306. std::cout << "file read finished with points " << pointcloud->size() << std::endl;
  307. return true;
  308. }