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. //
  84. //pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
  85. //{
  86. // std::ifstream fin(file.c_str());
  87. // const int line_length=64;
  88. // char str[line_length]={0};
  89. // pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  90. // while(fin.getline(str,line_length))
  91. // {
  92. // pcl::PointXYZ point;
  93. // if(string2point(str,point))
  94. // {
  95. // cloud->push_back(point);
  96. // }
  97. // }
  98. // return cloud;
  99. //}
  100. //
  101. void save_cloud_txt(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,std::string file)
  102. {
  103. FILE* pf=fopen(file.c_str(),"w");
  104. for(int i=0;i<cloud->size();++i)
  105. {
  106. pcl::PointXYZ point=cloud->points[i];
  107. fprintf(pf,"%.3f %.3f %.3f\n",point.x,point.y,point.z);
  108. }
  109. fclose(pf);
  110. }
  111. void save_cloud_txt(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,std::string file)
  112. {
  113. FILE* pf=fopen(file.c_str(),"w");
  114. for(int i=0;i<cloud->size();++i)
  115. {
  116. pcl::PointXYZRGB point=cloud->points[i];
  117. fprintf(pf,"%.3f %.3f %.3f %d %d %d\n",point.x,point.y,point.z,point.r,point.g,point.b);
  118. }
  119. fclose(pf);
  120. }
  121. //欧式聚类*******************************************************
  122. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  123. {
  124. std::vector<pcl::PointIndices> ece_inlier;
  125. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  126. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  127. ece.setInputCloud(sor_cloud);
  128. ece.setClusterTolerance(0.2);
  129. ece.setMinClusterSize(20);
  130. ece.setMaxClusterSize(20000);
  131. ece.setSearchMethod(tree);
  132. ece.extract(ece_inlier);
  133. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  134. for (int i = 0; i < ece_inlier.size(); i++)
  135. {
  136. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  137. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  138. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy);//按照索引提取点云数据
  139. segmentation_clouds.push_back(cloud_copy);
  140. }
  141. return segmentation_clouds;
  142. }
  143. //
  144. //double distance(cv::Point2f p1, cv::Point2f p2)
  145. //{
  146. // return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  147. //}
  148. bool isRect(std::vector<cv::Point2f>& points)
  149. {
  150. if (points.size() == 4)
  151. {
  152. double L[3] = {0.0};
  153. L[0] = distance(points[0], points[1]);
  154. L[1] = distance(points[1], points[2]);
  155. L[2] = distance(points[0], points[2]);
  156. double max_l = L[0];
  157. double l1 = L[1];
  158. double l2 = L[2];
  159. cv::Point2f ps = points[0], pt = points[1];
  160. cv::Point2f pc = points[2];
  161. for (int i = 1; i < 3; ++i) {
  162. if (L[i] > max_l)
  163. {
  164. max_l = L[i];
  165. l1 = L[abs(i + 1) % 3];
  166. l2 = L[abs(i + 2) % 3];
  167. ps = points[i % 3];
  168. pt = points[(i + 1) % 3];
  169. pc = points[(i + 2) % 3];
  170. }
  171. }
  172. //直角边与坐标轴的夹角 <20°
  173. float thresh=20.0*M_PI/180.0;
  174. cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
  175. float angle=atan2(vct.y,vct.x);
  176. if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
  177. {
  178. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  179. return false;
  180. }
  181. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  182. if (fabs(cosa) >= 0.15) {
  183. /*char description[255]={0};
  184. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  185. std::cout<<description<<std::endl;*/
  186. return false;
  187. }
  188. float width=std::min(l1,l2);
  189. float length=std::max(l1,l2);
  190. if(width<1.400 || width >1.900 || length >3.300 ||length < 2.200)
  191. {
  192. /*char description[255]={0};
  193. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  194. std::cout<<description<<std::endl;*/
  195. return false;
  196. }
  197. double d = distance(pc, points[3]);
  198. cv::Point2f center1 = (ps + pt) * 0.5;
  199. cv::Point2f center2 = (pc + points[3]) * 0.5;
  200. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150) {
  201. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  202. char description[255]={0};
  203. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  204. std::cout<<description<<std::endl;*/
  205. return false;
  206. }
  207. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  208. return true;
  209. }
  210. else if(points.size()==3)
  211. {
  212. double L[3] = {0.0};
  213. L[0] = distance(points[0], points[1]);
  214. L[1] = distance(points[1], points[2]);
  215. L[2] = distance(points[0], points[2]);
  216. double max_l = L[0];
  217. double l1 = L[1];
  218. double l2 = L[2];
  219. int max_index = 0;
  220. cv::Point2f ps = points[0], pt = points[1];
  221. cv::Point2f pc = points[2];
  222. for (int i = 1; i < 3; ++i) {
  223. if (L[i] > max_l) {
  224. max_index = i;
  225. max_l = L[i];
  226. l1 = L[abs(i + 1) % 3];
  227. l2 = L[abs(i + 2) % 3];
  228. ps = points[i % 3];
  229. pt = points[(i + 1) % 3];
  230. pc = points[(i + 2) % 3];
  231. }
  232. }
  233. //直角边与坐标轴的夹角 <20°
  234. float thresh=20.0*M_PI/180.0;
  235. cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
  236. float angle=atan2(vct.y,vct.x);
  237. if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
  238. {
  239. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  240. return false;
  241. }
  242. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  243. if (fabs(cosa) >= 0.15) {
  244. /*char description[255]={0};
  245. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  246. std::cout<<description<<std::endl;*/
  247. return false;
  248. }
  249. double l=std::max(l1,l2);
  250. double w=std::min(l1,l2);
  251. if(l>2.100 && l<3.300 && w>1.400 && w<2.100)
  252. {
  253. //生成第四个点
  254. cv::Point2f vec1=ps-pc;
  255. cv::Point2f vec2=pt-pc;
  256. cv::Point2f point4=(vec1+vec2)+pc;
  257. points.push_back(point4);
  258. /*char description[255]={0};
  259. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  260. std::cout<<description<<std::endl;*/
  261. return true;
  262. }
  263. else
  264. {
  265. /*char description[255]={0};
  266. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  267. std::cout<<description<<std::endl;*/
  268. return false;
  269. }
  270. }
  271. //std::cout<<" default false"<<std::endl;
  272. return false;
  273. }
  274. bool read_pointcloud(std::string filename, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud)
  275. {
  276. // std::lock_guard<std::mutex> lck(m_cloud_mutex);
  277. pointcloud->clear();
  278. std::ifstream in(filename);
  279. if (!in.is_open())
  280. {
  281. std::cout << "failed to open file " << filename << std::endl;
  282. return false;
  283. }
  284. while (!in.eof())
  285. {
  286. std::string t_linestr;
  287. if (getline(in, t_linestr))
  288. {
  289. std::vector<std::string> str_vector;
  290. std::stringstream ss(t_linestr);
  291. std::string num_str;
  292. while (getline(ss, num_str, ' '))
  293. {
  294. str_vector.push_back(num_str);
  295. }
  296. if (str_vector.size() != 3)
  297. {
  298. std::cout << "unsupported point cloud / cannot find point x y z value: " << filename << std::endl;
  299. return false;
  300. }
  301. pcl::PointXYZ t_cloud;
  302. t_cloud.x = stod(str_vector[0]);
  303. t_cloud.y = stod(str_vector[1]);
  304. t_cloud.z = stod(str_vector[2]);
  305. pointcloud->push_back(t_cloud);
  306. }
  307. }
  308. in.close();
  309. std::cout << "file read finished with points " << pointcloud->size() << std::endl;
  310. return true;
  311. }