main.cpp 9.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299
  1. #include <QCoreApplication>
  2. #include "lidar_obstacle_detector/obstacle_detector.hpp"
  3. #include <iostream>
  4. #include "modulecomm.h"
  5. #include "ivstdcolorout.h"
  6. #include "objectarray.pb.h"
  7. using namespace lidar_obstacle_detector;
  8. // Pointcloud Filtering Parameters
  9. static bool USE_PCA_BOX;
  10. static bool USE_TRACKING;
  11. static float VOXEL_GRID_SIZE;
  12. static Eigen::Vector4f ROI_MAX_POINT, ROI_MIN_POINT;
  13. static float GROUND_THRESH;
  14. static float CLUSTER_THRESH;
  15. static int CLUSTER_MAX_SIZE, CLUSTER_MIN_SIZE;
  16. static float DISPLACEMENT_THRESH, IOU_THRESH;
  17. static size_t obstacle_id_;
  18. static std::string bbox_target_frame_, bbox_source_frame_;
  19. static std::vector<Box> prev_boxes_, curr_boxes_;
  20. static std::shared_ptr<ObstacleDetector<pcl::PointXYZ>> obstacle_detector;
  21. static void * gpa_cluster,*gpa_ground,* gpa_detect;
  22. struct Quaternion {
  23. double w, x, y, z;
  24. };
  25. struct EulerAngles {
  26. double roll, pitch, yaw;
  27. };
  28. EulerAngles ToEulerAngles(Quaternion q) {
  29. EulerAngles angles;
  30. // roll (x-axis rotation)
  31. double sinr_cosp = 2 * (q.w * q.x + q.y * q.z);
  32. double cosr_cosp = 1 - 2 * (q.x * q.x + q.y * q.y);
  33. angles.roll = std::atan2(sinr_cosp, cosr_cosp);
  34. // pitch (y-axis rotation)
  35. double sinp = 2 * (q.w * q.y - q.z * q.x);
  36. if (std::abs(sinp) >= 1)
  37. angles.pitch = std::copysign(M_PI / 2, sinp); // use 90 degrees if out of range
  38. else
  39. angles.pitch = std::asin(sinp);
  40. // yaw (z-axis rotation)
  41. double siny_cosp = 2 * (q.w * q.z + q.x * q.y);
  42. double cosy_cosp = 1 - 2 * (q.y * q.y + q.z * q.z);
  43. angles.yaw = std::atan2(siny_cosp, cosy_cosp);
  44. return angles;
  45. }
  46. void publishDetectedObjects(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>&& cloud_clusters)
  47. {
  48. iv::lidar::objectarray lidarobjvec;
  49. for (auto& cluster : cloud_clusters)
  50. {
  51. // Create Bounding Boxes
  52. Box box = USE_PCA_BOX?
  53. obstacle_detector->pcaBoundingBox(cluster, obstacle_id_) :
  54. obstacle_detector->axisAlignedBoundingBox(cluster, obstacle_id_);
  55. obstacle_id_ = (obstacle_id_ < SIZE_MAX)? ++obstacle_id_ : 0;
  56. curr_boxes_.emplace_back(box);
  57. }
  58. // Re-assign Box ids based on tracking result
  59. if (USE_TRACKING)
  60. obstacle_detector->obstacleTracking(prev_boxes_, curr_boxes_, DISPLACEMENT_THRESH, IOU_THRESH);
  61. ivstdcolorout("Print Objects:",iv::STDCOLOR_BOLDGREEN);
  62. // Transform boxes from lidar frame to base_link frame, and convert to jsk and autoware msg formats
  63. for (auto& box : curr_boxes_)
  64. {
  65. std::cout<<" box x y z "<<box.position(0)<<" "<<box.position(1)<<" "<<box.position(2)<<std::endl;
  66. // geometry_msgs::Pose pose, pose_transformed;
  67. // pose.position.x = box.position(0);
  68. // pose.position.y = box.position(1);
  69. // pose.position.z = box.position(2);
  70. // pose.orientation.w = box.quaternion.w();
  71. // pose.orientation.x = box.quaternion.x();
  72. // pose.orientation.y = box.quaternion.y();
  73. // pose.orientation.z = box.quaternion.z();
  74. // tf2::doTransform(pose, pose_transformed, transform_stamped);
  75. // jsk_bboxes.boxes.emplace_back(transformJskBbox(box, bbox_header, pose_transformed));
  76. // autoware_objects.objects.emplace_back(transformAutowareObject(box, bbox_header, pose_transformed));
  77. iv::lidar::lidarobject * plidarobj = lidarobjvec.add_obj();
  78. iv::lidar::PointXYZ center;
  79. iv::lidar::Dimension xdim;
  80. center.set_x(box.position(0));
  81. center.set_y(box.position(1));
  82. center.set_z(box.position(2));
  83. xdim.set_x(box.dimension(0));
  84. xdim.set_y(box.dimension(1));
  85. xdim.set_z(box.dimension(2));
  86. EulerAngles xAng;
  87. Quaternion xQuat;
  88. xQuat.w = box.quaternion.w();
  89. xQuat.x = box.quaternion.x();
  90. xQuat.y = box.quaternion.y();
  91. xQuat.z = box.quaternion.z();
  92. xAng = ToEulerAngles(xQuat);
  93. plidarobj->set_id(box.id);
  94. plidarobj->set_tyaw(xAng.yaw);
  95. plidarobj->mutable_position()->CopyFrom(center);
  96. plidarobj->mutable_centroid()->CopyFrom(center);
  97. plidarobj->mutable_dimensions()->CopyFrom(xdim);
  98. }
  99. unsigned int ndatasize = lidarobjvec.ByteSize();
  100. std::shared_ptr<char> pstr_data = std::shared_ptr<char>(new char[ndatasize]);
  101. if(lidarobjvec.SerializeToArray(pstr_data.get(),static_cast<int>(ndatasize) ))
  102. {
  103. iv::modulecomm::ModuleSendMsg(gpa_detect,pstr_data.get(),ndatasize);
  104. }
  105. else
  106. {
  107. ivstdcolorout("Serialzie detect error.",iv::STDCOLOR_BOLDRED);
  108. }
  109. // char * strout = lidarobjtostr(lidarobjvec,ntlen);
  110. // Update previous bounding boxes
  111. prev_boxes_.swap(curr_boxes_);
  112. curr_boxes_.clear();
  113. }
  114. void sharepointcloud(void * pa,pcl::PointCloud<pcl::PointXYZI>::Ptr & point_cloud)
  115. {
  116. char * strOut = new char[4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI)];
  117. int * pHeadSize = reinterpret_cast<int * >(strOut);
  118. *pHeadSize = static_cast<int >(4 + point_cloud->header.frame_id.size()+4+8) ;
  119. memcpy(strOut+4,point_cloud->header.frame_id.c_str(),point_cloud->header.frame_id.size());
  120. uint32_t * pu32 = reinterpret_cast<uint32_t *>(strOut+4+sizeof(point_cloud->header.frame_id.size()));
  121. *pu32 = point_cloud->header.seq;
  122. memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
  123. pcl::PointXYZI * p;
  124. p = reinterpret_cast<pcl::PointXYZI *>(strOut +4+sizeof(point_cloud->header.frame_id.size()) + 4+8 );
  125. memcpy(p,point_cloud->points.data(),point_cloud->width * sizeof(pcl::PointXYZI));
  126. std::cout<<"width: "<<point_cloud->width<<std::endl;
  127. iv::modulecomm::ModuleSendMsg(pa,strOut,4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI));
  128. delete [] strOut;
  129. }
  130. void sharepointxyz( pcl::PointCloud<pcl::PointXYZ>::Ptr &raw_cloud,void * pa)
  131. {
  132. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  133. new pcl::PointCloud<pcl::PointXYZI>());
  134. point_cloud->header.frame_id = "velodyne";
  135. point_cloud->header.seq = 1;
  136. point_cloud->header.stamp = 0;
  137. int nPCount = raw_cloud->points.size();
  138. std::cout<<" size: "<<nPCount<<std::endl;
  139. int i;
  140. for(i=0;i<nPCount;i++)
  141. {
  142. pcl::PointXYZI xp;
  143. xp.x = raw_cloud->points.at(i).x;
  144. xp.y = raw_cloud->points.at(i).y;
  145. xp.z = raw_cloud->points.at(i).z;
  146. xp.intensity = 100;
  147. point_cloud->push_back(xp);
  148. }
  149. sharepointcloud(pa,point_cloud);
  150. }
  151. void DectectOnePCD(const pcl::PointCloud<pcl::PointXYZ>::Ptr &raw_cloud)
  152. {
  153. // Downsampleing, ROI, and removing the car roof
  154. auto filtered_cloud = obstacle_detector->filterCloud(raw_cloud, VOXEL_GRID_SIZE, ROI_MIN_POINT, ROI_MAX_POINT);
  155. // Segment the groud plane and obstacles
  156. auto segmented_clouds = obstacle_detector->segmentPlane(filtered_cloud, 30, GROUND_THRESH);
  157. // Cluster objects
  158. auto cloud_clusters = obstacle_detector->clustering(segmented_clouds.first, CLUSTER_THRESH, CLUSTER_MIN_SIZE, CLUSTER_MAX_SIZE);
  159. publishDetectedObjects(std::move(cloud_clusters));
  160. sharepointxyz(segmented_clouds.first,gpa_cluster);
  161. sharepointxyz(segmented_clouds.second,gpa_ground);
  162. }
  163. void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  164. {
  165. if(nSize <=16)return;
  166. unsigned int * pHeadSize = (unsigned int *)strdata;
  167. if(*pHeadSize > nSize)
  168. {
  169. std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
  170. }
  171. QTime xTime;
  172. xTime.start();
  173. pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud(
  174. new pcl::PointCloud<pcl::PointXYZ>());
  175. int nNameSize;
  176. nNameSize = *pHeadSize - 4-4-8;
  177. char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
  178. memcpy(strName,(char *)((char *)strdata +4),nNameSize);
  179. point_cloud->header.frame_id = strName;
  180. memcpy(&point_cloud->header.seq,(char *)strdata+4+nNameSize,4);
  181. memcpy(&point_cloud->header.stamp,(char *)strdata+4+nNameSize+4,8);
  182. int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
  183. int i;
  184. pcl::PointXYZI * p;
  185. p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
  186. for(i=0;i<nPCount;i++)
  187. {
  188. pcl::PointXYZ xp;
  189. // if((p->x<-30)||(p->x>30)||(p->y>50)||(p->y<-50))
  190. // {
  191. // }
  192. // else
  193. // {
  194. // memcpy(&xp,p,sizeof(pcl::PointXYZI));
  195. // xp.z = xp.z;
  196. xp.x = p->x;
  197. xp.y = p->y;
  198. xp.z = p->z;
  199. point_cloud->push_back(xp);
  200. // }
  201. p++;
  202. // xp.x = p->x;
  203. // xp.y = p->y;
  204. // xp.z = p->z;
  205. // xp.intensity = p->intensity;
  206. // point_cloud->push_back(xp);
  207. // p++;
  208. }
  209. // std::cout<<"pcl time is "<<xTime.elapsed()<<std::endl;
  210. DectectOnePCD(point_cloud);
  211. std::cout<<"time is "<<(QDateTime::currentMSecsSinceEpoch() % 1000)<<" use: "<<xTime.elapsed()<<std::endl;
  212. }
  213. int main(int argc, char *argv[])
  214. {
  215. QCoreApplication a(argc, argv);
  216. USE_PCA_BOX = false;
  217. USE_TRACKING = true;
  218. VOXEL_GRID_SIZE = 0.2;
  219. ROI_MAX_POINT = Eigen::Vector4f(70,30,1,1);
  220. ROI_MIN_POINT = Eigen::Vector4f(-30,-30,-2.5, 1);
  221. GROUND_THRESH = 0.3;
  222. CLUSTER_THRESH = 0.6;
  223. CLUSTER_MAX_SIZE = 5000;
  224. CLUSTER_MIN_SIZE = 10;
  225. DISPLACEMENT_THRESH = 1.0;
  226. IOU_THRESH = 1.0;
  227. obstacle_detector = std::make_shared<ObstacleDetector<pcl::PointXYZ>>();
  228. gpa_detect = iv::modulecomm::RegisterSend("lidar_pointpillar",10000000,1);
  229. gpa_cluster = iv::modulecomm::RegisterSend("lidarpc_cluster",10000000,1);
  230. gpa_ground = iv::modulecomm::RegisterSend("lidarpc_ground",10000000,1);
  231. void * pa = iv::modulecomm::RegisterRecv("lidar_pc",ListenPointCloud);
  232. return a.exec();
  233. }