lidarmerge.cpp 3.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485
  1. #include "lidarmerge.h"
  2. #include <QDateTime>
  3. #include <QMutex>
  4. extern QMutex gMutex;
  5. static int g_seq = 0;
  6. pcl::PointCloud<pcl::PointXYZI>::Ptr mergefunc(std::vector<iv::lidar_data> xvectorlidar)
  7. {
  8. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  9. new pcl::PointCloud<pcl::PointXYZI>());
  10. point_cloud->header.frame_id = "velodyne";
  11. point_cloud->height = 1;
  12. point_cloud->header.stamp = QDateTime::currentMSecsSinceEpoch();
  13. point_cloud->width = 0;
  14. point_cloud->header.seq =g_seq;
  15. g_seq++;
  16. int i,j;
  17. for(i=0;i<xvectorlidar.size();i++)
  18. {
  19. Eigen::Matrix3d rotation_matrix;
  20. Eigen::Vector3d trans_matrix;
  21. Eigen::AngleAxisd r_z ( xvectorlidar[i].fang_z/180.0*M_PI, Eigen::Vector3d ( 0,0,1 ) ); //沿 Z 轴旋转 yaw
  22. Eigen::AngleAxisd r_y ( xvectorlidar[i].fang_y/180.0*M_PI, Eigen::Vector3d ( 0,1,0 ) ); //沿 Y 轴旋转 roll
  23. Eigen::AngleAxisd r_x ( xvectorlidar[i].fang_x/180.0*M_PI, Eigen::Vector3d ( 1,0,0 ) ); //沿 X 轴旋转 pitch
  24. Eigen::Quaterniond q_zyx = r_z*r_y*r_x; //ZYX旋转顺序
  25. // 四元数-->>旋转矩阵
  26. rotation_matrix = q_zyx.toRotationMatrix();
  27. trans_matrix << xvectorlidar[i].foff_x, xvectorlidar[i].foff_y, xvectorlidar[i].foff_z;//x,y,z
  28. int nsize;
  29. pcl::PointCloud<pcl::PointXYZI>::Ptr partpoint_cloud;
  30. int64_t curtime = QDateTime::currentMSecsSinceEpoch();
  31. if((xvectorlidar[i].bUpdate)||((curtime -xvectorlidar[i].mupdatetime)<150))
  32. {
  33. gMutex.lock();
  34. partpoint_cloud = xvectorlidar[i].mpoint_cloud;
  35. gMutex.unlock();
  36. nsize = partpoint_cloud->width;
  37. qDebug("size is %d ",nsize);
  38. for(j=0;j<nsize;j++)
  39. {
  40. pcl::PointXYZI point;
  41. point = partpoint_cloud->at(j);
  42. Eigen::Vector3d new_point, old_point;
  43. old_point<<point.x, point.y, point.z;
  44. new_point = rotation_matrix * (old_point) + trans_matrix;
  45. point.x = new_point[0];
  46. point.y = new_point[1];
  47. point.z = new_point[2];
  48. if(point.x>xvectorlidar[i].fmax_x)continue;
  49. if(point.y>xvectorlidar[i].fmax_y)continue;
  50. if(point.z>xvectorlidar[i].fmax_z)continue;
  51. if(point.z > xvectorlidar[i].fignore_zmax) continue;
  52. if(point.z < xvectorlidar[i].fignore_zmin) continue;
  53. // std::cout<<" fignore zmin "<<xvectorlidar[i].fignore_zmin<<std::endl;
  54. if(point.x<xvectorlidar[i].fmin_x)continue;
  55. if(point.y<xvectorlidar[i].fmin_y)continue;
  56. if(point.z<xvectorlidar[i].fmin_z)continue;
  57. if((point.x>xvectorlidar[i].fignore_xmin)&&(point.x<xvectorlidar[i].fignore_xmax)&&(point.y>xvectorlidar[i].fignore_ymin)&&(point.y<xvectorlidar[i].fignore_ymax))
  58. {
  59. continue;
  60. }
  61. if(!pcl_isfinite(point.x)||!pcl_isfinite(point.y)||!pcl_isfinite(point.z)||!pcl_isfinite(point.intensity)) continue;
  62. point_cloud->push_back(point);
  63. ++point_cloud->width;
  64. }
  65. }
  66. }
  67. qDebug("merge size is %d ",point_cloud->width);
  68. return point_cloud;
  69. }