main.cpp 7.5 KB

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