main.cpp 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189
  1. #include <QCoreApplication>
  2. #include <iostream>
  3. #include <sstream>
  4. #include <fstream>
  5. #include <pcl/point_types.h>
  6. #include <pcl/point_cloud.h>
  7. #include "cuda_runtime.h"
  8. #include "./params.h"
  9. #include "./pointpillar.h"
  10. #include "modulecomm.h"
  11. std::string Model_File = "/home/nvidia/models/lidar/pointpillar.onnx";
  12. PointPillar * gpPointPillar;
  13. cudaEvent_t start, stop;
  14. float elapsedTime = 0.0f;
  15. cudaStream_t stream = NULL;
  16. std::vector<Bndbox> nms_pred;
  17. #define checkCudaErrors(status) \
  18. { \
  19. if (status != 0) \
  20. { \
  21. std::cout << "Cuda failure: " << cudaGetErrorString(status) \
  22. << " at line " << __LINE__ \
  23. << " in file " << __FILE__ \
  24. << " error status: " << status \
  25. << std::endl; \
  26. abort(); \
  27. } \
  28. }
  29. void Getinfo(void)
  30. {
  31. cudaDeviceProp prop;
  32. int count = 0;
  33. cudaGetDeviceCount(&count);
  34. printf("\nGPU has cuda devices: %d\n", count);
  35. for (int i = 0; i < count; ++i) {
  36. cudaGetDeviceProperties(&prop, i);
  37. printf("----device id: %d info----\n", i);
  38. printf(" GPU : %s \n", prop.name);
  39. printf(" Capbility: %d.%d\n", prop.major, prop.minor);
  40. printf(" Global memory: %luMB\n", prop.totalGlobalMem >> 20);
  41. printf(" Const memory: %luKB\n", prop.totalConstMem >> 10);
  42. printf(" SM in a block: %luKB\n", prop.sharedMemPerBlock >> 10);
  43. printf(" warp size: %d\n", prop.warpSize);
  44. printf(" threads in a block: %d\n", prop.maxThreadsPerBlock);
  45. printf(" block dim: (%d,%d,%d)\n", prop.maxThreadsDim[0], prop.maxThreadsDim[1], prop.maxThreadsDim[2]);
  46. printf(" grid dim: (%d,%d,%d)\n", prop.maxGridSize[0], prop.maxGridSize[1], prop.maxGridSize[2]);
  47. }
  48. printf("\n");
  49. }
  50. //void DectectOneBin(std::shared_ptr<float> & pbin_ptr,const int points_size)
  51. void DectectOneBin(float * pdata,const int points_size)
  52. {
  53. float *points_data = nullptr;
  54. unsigned int points_data_size = points_size * 4 * sizeof(float);
  55. checkCudaErrors(cudaMallocManaged((void **)&points_data, points_data_size));
  56. // checkCudaErrors(cudaMemcpy(points_data, pbin_ptr.get(), points_data_size, cudaMemcpyDefault));
  57. checkCudaErrors(cudaMemcpy(points_data, pdata, points_data_size, cudaMemcpyDefault));
  58. checkCudaErrors(cudaDeviceSynchronize());
  59. cudaEventRecord(start, stream);
  60. gpPointPillar->doinfer(points_data, points_size, nms_pred);
  61. cudaEventRecord(stop, stream);
  62. cudaEventSynchronize(stop);
  63. cudaEventElapsedTime(&elapsedTime, start, stop);
  64. std::cout<<"TIME: pointpillar: "<< elapsedTime <<" ms." <<std::endl;
  65. checkCudaErrors(cudaFree(points_data));
  66. std::cout<<"Bndbox objs: "<< nms_pred.size()<<std::endl;
  67. // std::string save_file_name = Save_Dir + index_str + ".txt";
  68. // SaveBoxPred(nms_pred, save_file_name);
  69. for (const auto box : nms_pred) {
  70. if(box.id != 0)continue;
  71. std::cout << box.x << " ";
  72. std::cout << box.y << " ";
  73. std::cout << box.z << " ";
  74. std::cout << box.w << " ";
  75. std::cout << box.l << " ";
  76. std::cout << box.h << " ";
  77. std::cout << box.rt << " ";
  78. std::cout << box.id << " ";
  79. std::cout << box.score << " ";
  80. std::cout << std::endl;
  81. }
  82. nms_pred.clear();
  83. delete pdata;
  84. std::cout << ">>>>>>>>>>>" <<std::endl;
  85. }
  86. void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  87. {
  88. if(nSize <=16)return;
  89. unsigned int * pHeadSize = (unsigned int *)strdata;
  90. if(*pHeadSize > nSize)
  91. {
  92. std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
  93. }
  94. int nNameSize;
  95. nNameSize = *pHeadSize - 4-4-8;
  96. char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
  97. memcpy(strName,(char *)((char *)strdata +4),nNameSize);
  98. int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
  99. int i;
  100. pcl::PointXYZI * p;
  101. p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
  102. std::shared_ptr<float> pbin_ptr = std::shared_ptr<float>(new float[nPCount*4]);
  103. float * pdata = new float[nPCount * 4];// pbin_ptr.get();
  104. for(i=0;i<nPCount;i++)
  105. {
  106. pcl::PointXYZI xp;
  107. memcpy(&xp,p,sizeof(pcl::PointXYZI));
  108. xp.z = xp.z;
  109. pdata[4*i + 0]= static_cast<float>(xp.x);
  110. pdata[4*i + 1]= static_cast<float>(xp.y);
  111. pdata[4*i + 2]= static_cast<float>(xp.z);
  112. pdata[4*i + 3]= static_cast<float>(xp.intensity);
  113. // pdata[4*i + 0]= 0;
  114. // pdata[4*i + 1]= 0;
  115. // pdata[4*i + 2]= 0;
  116. // pdata[4*i + 3]= 0;
  117. p++;
  118. }
  119. DectectOneBin(pdata,nPCount);
  120. // DectectOneBin(pbin_ptr,nPCount);
  121. }
  122. int main(int argc, char *argv[])
  123. {
  124. QCoreApplication a(argc, argv);
  125. Getinfo();
  126. checkCudaErrors(cudaEventCreate(&start));
  127. checkCudaErrors(cudaEventCreate(&stop));
  128. checkCudaErrors(cudaStreamCreate(&stream));
  129. Params params_;
  130. nms_pred.reserve(100);
  131. PointPillar pointpillar(Model_File, stream);
  132. gpPointPillar = &pointpillar;
  133. void * pa = iv::modulecomm::RegisterRecv("lidarpc_center",ListenPointCloud);
  134. return a.exec();
  135. checkCudaErrors(cudaEventDestroy(start));
  136. checkCudaErrors(cudaEventDestroy(stop));
  137. checkCudaErrors(cudaStreamDestroy(stream));
  138. }