main.cpp 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236
  1. #include <QCoreApplication>
  2. #include <yaml-cpp/yaml.h>
  3. #include <lidar_centerpoint/centerpoint_config.hpp>
  4. #include <lidar_centerpoint/centerpoint_trt.hpp>
  5. #include <lidar_centerpoint/preprocess/pointcloud_densification.hpp>
  6. #include "objectarray.pb.h"
  7. #include "modulecomm.h"
  8. void * gpa;
  9. void * gpdetect;
  10. using namespace centerpoint;
  11. std::unique_ptr<CenterPointTRT> detector_ptr_{nullptr};
  12. std::vector<std::string> class_names_;
  13. void LoadYaml(std::string stryamlname,std::vector<int64_t> & allow_remapping_by_area_matrix
  14. )
  15. {
  16. }
  17. void init()
  18. {
  19. const float score_threshold = 0.35;
  20. const float circle_nms_dist_threshold =0.5;
  21. // static_cast<float>(this->declare_parameter<double>("circle_nms_dist_threshold"));
  22. std::vector<double> yaw_norm_thresholds ;
  23. yaw_norm_thresholds.push_back(0.3);yaw_norm_thresholds.push_back(0.3);yaw_norm_thresholds.push_back(0.3);
  24. yaw_norm_thresholds.push_back(0.3);yaw_norm_thresholds.push_back(0.0);
  25. const std::string densification_world_frame_id = "map";
  26. const int densification_num_past_frames = 0;//1;
  27. const std::string trt_precision = "fp16";
  28. const std::string encoder_onnx_path = "/home/nvidia/models/pts_voxel_encoder_centerpoint.onnx";//this->declare_parameter<std::string>("encoder_onnx_path");
  29. const std::string encoder_engine_path ="/home/nvidia/models/pts_voxel_encoder_centerpoint.eng";//this->declare_parameter<std::string>("encoder_engine_path");
  30. const std::string head_onnx_path = "/home/nvidia/models/pts_backbone_neck_head_centerpoint.onnx";//this->declare_parameter<std::string>("head_onnx_path");
  31. const std::string head_engine_path ="/home/nvidia/models/pts_backbone_neck_head_centerpoint.eng" ;//this->declare_parameter<std::string>("head_engine_path");
  32. const std::size_t point_feature_size =4;
  33. const std::size_t max_voxel_size =40000;
  34. std::vector<double> point_cloud_range ;
  35. point_cloud_range.push_back(-76.8);point_cloud_range.push_back(-76.8);
  36. point_cloud_range.push_back(-4.0);point_cloud_range.push_back(76.8);
  37. point_cloud_range.push_back(76.8);point_cloud_range.push_back(6.0);
  38. std::vector<double>voxel_size ;
  39. voxel_size.push_back(0.32);voxel_size.push_back(0.32);
  40. voxel_size.push_back(10.0);
  41. const std::size_t downsample_factor =1;
  42. const std::size_t encoder_in_feature_size = 9;
  43. std::vector<int64_t> allow_remapping_by_area_matrix;
  44. std::vector<double> min_area_matrix ;
  45. std::vector<double> max_area_matrix ;
  46. class_names_.push_back("CAR");
  47. class_names_.push_back("TRUCK");
  48. class_names_.push_back("BUS");
  49. class_names_.push_back("BICYCLE");
  50. class_names_.push_back("PEDESTRIAN");
  51. NetworkParam encoder_param(encoder_onnx_path, encoder_engine_path, trt_precision);
  52. NetworkParam head_param(head_onnx_path, head_engine_path, trt_precision);
  53. DensificationParam densification_param(
  54. densification_world_frame_id, densification_num_past_frames);
  55. CenterPointConfig config(
  56. 5, point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
  57. downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
  58. yaw_norm_thresholds);
  59. detector_ptr_ =
  60. std::make_unique<CenterPointTRT>(encoder_param, head_param, densification_param, config);
  61. std::cout<<"init complete."<<std::endl;
  62. }
  63. void box3DToDetectedObject(
  64. const Box3D & box3d, const std::vector<std::string> & class_names, const bool has_twist,
  65. iv::lidar::lidarobject & obj)
  66. {
  67. // TODO(yukke42): the value of classification confidence of DNN, not probability.
  68. // obj.existence_probability = box3d.score;
  69. obj.set_score(box3d.score);
  70. // classification
  71. if (box3d.label >= 0 && static_cast<size_t>(box3d.label) < class_names.size()) {
  72. obj.set_type_name(class_names_[box3d.label]);
  73. } else {
  74. obj.set_type_name("UNKNOWN");
  75. }
  76. obj.set_mntype(box3d.label);
  77. obj.set_tyaw(box3d.yaw);
  78. iv::lidar::PointXYZ pos;
  79. pos.set_x(box3d.x);pos.set_y(box3d.y);pos.set_z(box3d.z);
  80. iv::lidar::Dimension dim;
  81. dim.set_x(box3d.length);dim.set_y(box3d.width);dim.set_z(box3d.height);
  82. iv::lidar::PointXYZ * ppos = obj.mutable_position();
  83. ppos->CopyFrom(pos);
  84. iv::lidar::PointXYZ * pcen = obj.mutable_centroid();
  85. pcen->CopyFrom(pos);
  86. iv::lidar::Dimension * pdim = obj.mutable_dimensions();
  87. pdim->CopyFrom(dim);
  88. // twist
  89. if (has_twist) {
  90. // float vel_x = box3d.vel_x;
  91. // float vel_y = box3d.vel_y;
  92. // geometry_msgs::msg::Twist twist;
  93. // twist.linear.x = std::sqrt(std::pow(vel_x, 2) + std::pow(vel_y, 2));
  94. // twist.angular.z = 2 * (std::atan2(vel_y, vel_x) - yaw);
  95. // obj.kinematics.twist_with_covariance.twist = twist;
  96. // obj.kinematics.has_twist = has_twist;
  97. }
  98. }
  99. void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  100. {
  101. if(nSize <=16)return;
  102. unsigned int * pHeadSize = (unsigned int *)strdata;
  103. if(*pHeadSize > nSize)
  104. {
  105. std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
  106. }
  107. QTime xTime;
  108. xTime.start();
  109. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  110. new pcl::PointCloud<pcl::PointXYZI>());
  111. int nNameSize;
  112. nNameSize = *pHeadSize - 4-4-8;
  113. char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
  114. memcpy(strName,(char *)((char *)strdata +4),nNameSize);
  115. point_cloud->header.frame_id = strName;
  116. memcpy(&point_cloud->header.seq,(char *)strdata+4+nNameSize,4);
  117. memcpy(&point_cloud->header.stamp,(char *)strdata+4+nNameSize+4,8);
  118. int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
  119. int i;
  120. pcl::PointXYZI * p;
  121. p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
  122. for(i=0;i<nPCount;i++)
  123. {
  124. pcl::PointXYZI xp;
  125. // if((p->x<-30)||(p->x>30)||(p->y>50)||(p->y<-50))
  126. // {
  127. // }
  128. // else
  129. // {
  130. memcpy(&xp,p,sizeof(pcl::PointXYZI));
  131. xp.z = xp.z;
  132. point_cloud->push_back(xp);
  133. // }
  134. p++;
  135. // xp.x = p->x;
  136. // xp.y = p->y;
  137. // xp.z = p->z;
  138. // xp.intensity = p->intensity;
  139. // point_cloud->push_back(xp);
  140. // p++;
  141. }
  142. // std::cout<<"pcl time is "<<xTime.elapsed()<<std::endl;
  143. std::vector<Box3D> det_boxes3d;
  144. detector_ptr_ ->detect(point_cloud,det_boxes3d);
  145. std::cout<<" box size: "<<det_boxes3d.size()<<std::endl;
  146. iv::lidar::objectarray lidarobjvec;
  147. int nsize = static_cast<int>(det_boxes3d.size());
  148. for(i=0;i<nsize;i++)
  149. {
  150. iv::lidar::lidarobject obj;
  151. box3DToDetectedObject(det_boxes3d[i],class_names_,false,obj);
  152. iv::lidar::lidarobject * pobj = lidarobjvec.add_obj();
  153. pobj->CopyFrom(obj);
  154. std::cout<<" obj i: "<<i<<" class: "<<pobj->type_name()<<" x: "<<pobj->position().x()<<" y: "<<pobj->position().y()<<std::endl;
  155. }
  156. std::string out = lidarobjvec.SerializeAsString();
  157. // char * strout = lidarobjtostr(lidarobjvec,ntlen);
  158. iv::modulecomm::ModuleSendMsg(gpdetect,out.data(),out.length());
  159. }
  160. #include <pcl/io/pcd_io.h>
  161. void testdet(std::string & path)
  162. {
  163. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  164. new pcl::PointCloud<pcl::PointXYZI>());
  165. pcl::io::loadPCDFile<pcl::PointXYZI>(path,*point_cloud);
  166. std::vector<Box3D> det_boxes3d;
  167. int i;
  168. for(i=0;i<10;i++)
  169. {
  170. detector_ptr_ ->detect(point_cloud,det_boxes3d);
  171. std::cout<<" box size: "<<det_boxes3d.size()<<std::endl;
  172. }
  173. }
  174. int main(int argc, char *argv[])
  175. {
  176. QCoreApplication a(argc, argv);
  177. init();
  178. std::string path = "/home/nvidia/1.pcd";
  179. // testdet(path);
  180. gpa = iv::modulecomm::RegisterRecv("lidar_pc",ListenPointCloud);
  181. gpdetect = iv::modulecomm::RegisterSend("lidar_track",10000000,1);
  182. return a.exec();
  183. }