main.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372
  1. #include <QCoreApplication>
  2. #include <pcl/io/pcd_io.h>
  3. #include <chrono>
  4. #include <thread>
  5. #include "lidar_apollo_instance_segmentation/detector.hpp"
  6. #include "object.pb.h"
  7. #include "objectarray.pb.h"
  8. #include "modulecomm.h"
  9. #include "xmlparam.h"
  10. void * gpa;
  11. void * gpdetect;
  12. LidarApolloInstanceSegmentation * gseg;
  13. void test()
  14. {
  15. pcl::PointCloud<pcl::PointXYZI>::Ptr xpc(
  16. new pcl::PointCloud<pcl::PointXYZI>);
  17. pcl::PointCloud<pcl::PointXYZI>::Ptr xpcfile;
  18. xpcfile = boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI>>(new pcl::PointCloud<pcl::PointXYZI>);
  19. if(0 == pcl::io::loadPCDFile("/home/nvidia/share/middle.pcd",*xpc))
  20. {
  21. }
  22. else
  23. {
  24. std::cout<<"load pcd fail"<<std::endl;
  25. return;
  26. }
  27. int i;
  28. for(i=0;i<10;i++)
  29. {
  30. int64_t time1 = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  31. std::vector<Obstacle> objvec;
  32. gseg->detectDynamicObjects(
  33. xpc,
  34. objvec);
  35. int64_t time2 = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  36. std::cout<<"complete test. use "<<(time2 - time1)/1000<< std::endl;
  37. // std::this_thread::sleep_for(std::chrono::milliseconds(80));
  38. }
  39. std::cout<<"test complete."<<std::endl;
  40. }
  41. std::string gstrinput;
  42. std::string gstroutput;
  43. static iv::lidar::PointXYZ pcltoprotopoint(pcl::PointXYZ x)
  44. {
  45. iv::lidar::PointXYZ lx;
  46. lx.set_x(x.x);
  47. lx.set_y(x.y);
  48. lx.set_z(x.z);
  49. return lx;
  50. }
  51. static void GetLidarObj(std::vector<Obstacle> objvec,iv::lidar::objectarray & lidarobjvec)
  52. {
  53. int i;
  54. for(i=0;i<objvec.size();i++)
  55. {
  56. Obstacle x;
  57. iv::lidar::lidarobject lidarobj;
  58. // iv::lidar::object xo;
  59. x = objvec.at(i);
  60. pcl::PointCloud<pcl::PointXYZI> in_cluster = *x.cloud_ptr;
  61. float min_x = std::numeric_limits<float>::max();
  62. float max_x = -std::numeric_limits<float>::max();
  63. float min_y = std::numeric_limits<float>::max();
  64. float max_y = -std::numeric_limits<float>::max();
  65. float min_z = std::numeric_limits<float>::max();
  66. float max_z = -std::numeric_limits<float>::max();
  67. float average_x = 0, average_y = 0, average_z = 0;
  68. float length, width, height;
  69. pcl::PointXYZ min_point;
  70. pcl::PointXYZ max_point;
  71. // pcl::PointXYZ average_point;
  72. pcl::PointXYZ centroid;
  73. centroid.x = 0;
  74. centroid.y = 0;
  75. centroid.z = 0;
  76. for (auto pit = in_cluster.points.begin(); pit != in_cluster.points.end(); ++pit)
  77. {
  78. average_x += pit->x;
  79. average_y += pit->y;
  80. average_z += pit->z;
  81. centroid.x += pit->x;
  82. centroid.y += pit->y;
  83. centroid.z += pit->z;
  84. if (pit->x < min_x)
  85. min_x = pit->x;
  86. if (pit->y < min_y)
  87. min_y = pit->y;
  88. if (pit->z < min_z)
  89. min_z = pit->z;
  90. if (pit->x > max_x)
  91. max_x = pit->x;
  92. if (pit->y > max_y)
  93. max_y = pit->y;
  94. if (pit->z > max_z)
  95. max_z = pit->z;
  96. }
  97. // min, max points
  98. min_point.x = min_x;
  99. min_point.y = min_y;
  100. min_point.z = min_z;
  101. max_point.x = max_x;
  102. max_point.y = max_y;
  103. max_point.z = max_z;
  104. if (in_cluster.points.size() > 0)
  105. {
  106. centroid.x /= in_cluster.points.size();
  107. centroid.y /= in_cluster.points.size();
  108. centroid.z /= in_cluster.points.size();
  109. }
  110. length = max_point.x - min_point.x;
  111. width = max_point.y - min_point.y;
  112. height = max_point.z - min_point.z;
  113. iv::lidar::PointXYZ lx;
  114. iv::lidar::PointXYZ * plx;
  115. lx = pcltoprotopoint(centroid);
  116. plx = lidarobj.mutable_centroid();
  117. plx->CopyFrom(lx);
  118. lx = pcltoprotopoint(min_point);
  119. plx = lidarobj.mutable_min_point();
  120. plx->CopyFrom(lx);
  121. lx = pcltoprotopoint(max_point);
  122. plx = lidarobj.mutable_max_point();
  123. plx->CopyFrom(lx);
  124. // lidarobj.centroid = centroid;
  125. // lidarobj.min_point = min_point;
  126. // lidarobj.max_point = max_point;
  127. lx.set_x(min_point.x + length / 2);
  128. lx.set_y(min_point.y + width / 2);
  129. lx.set_z(min_point.z + height / 2);
  130. plx = lidarobj.mutable_position();
  131. plx->CopyFrom(lx);
  132. // lidarobj.position.x = min_point.x + length / 2;
  133. // lidarobj.position.y = min_point.y + width / 2;
  134. // lidarobj.position.z = min_point.z + height / 2;
  135. iv::lidar::Dimension ld;
  136. iv::lidar::Dimension * pld;
  137. ld.set_x((length < 0) ? -1 * length : length);
  138. ld.set_y((width < 0) ? -1 * width : width);
  139. ld.set_z((height < 0) ? -1 * height : height);
  140. // lidarobj.dimensions.x = ((length < 0) ? -1 * length : length);
  141. // lidarobj.dimensions.y = ((width < 0) ? -1 * width : width);
  142. // lidarobj.dimensions.z = ((height < 0) ? -1 * height : height);
  143. pld = lidarobj.mutable_dimensions();
  144. pld->CopyFrom(ld);
  145. lidarobj.set_mntype(x.meta_type);
  146. lidarobj.set_score(x.score);
  147. lidarobj.set_type_name(x.GetTypeString());
  148. int j;
  149. for(j=0;j<x.meta_type_probs.size();j++)
  150. {
  151. lidarobj.add_type_probs(x.meta_type_probs.at(j));
  152. }
  153. for(j=0;j<x.cloud_ptr->size();j++)
  154. {
  155. iv::lidar::PointXYZI * pcp = lidarobj.add_cloud();
  156. pcl::PointXYZI pp = x.cloud_ptr->at(j);
  157. pcp->set_x(pp.x);
  158. pcp->set_y(pp.y);
  159. pcp->set_z(pp.z);
  160. pcp->set_i(pp.intensity);
  161. }
  162. iv::lidar::lidarobject * po = lidarobjvec.add_obj();
  163. po->CopyFrom(lidarobj);
  164. // givlog->verbose("CNNOBJ"," object %d type:%s x:%6.3f y:%6.3f",i,
  165. // lidarobj.type_name().data(),lidarobj.position().x(),
  166. // lidarobj.position().y());
  167. // lidarobj.mnType = x.meta_type;
  168. // lidarobj.score = x.score;
  169. // lidarobj.type_probs = x.meta_type_probs;
  170. // lidarobj.cloud_ptr = x.cloud_ptr;
  171. // int ndatalen;
  172. // char * strx = lidarobj.serialize(ndatalen);
  173. // lidarobj.unserialize(strx,ndatalen);
  174. // delete strx;
  175. // lidarobjvec.push_back(lidarobj);
  176. }
  177. }
  178. void DectectOnePCD(const pcl::PointCloud<pcl::PointXYZI>::Ptr &pc_ptr)
  179. {
  180. std::cout<<"pcd size is "<<pc_ptr->size()<<std::endl;
  181. pcl::PointIndices valid_idx;
  182. auto &indices = valid_idx.indices;
  183. indices.resize(pc_ptr->size());
  184. std::iota(indices.begin(), indices.end(), 0);
  185. std::vector<Obstacle> objvec;
  186. gseg->detectDynamicObjects(
  187. pc_ptr,
  188. objvec);
  189. std::cout<<"obj size is "<<objvec.size()<<std::endl;
  190. // std::vector<iv::lidar::lidarobject> lidarobjvec;
  191. iv::lidar::objectarray lidarobjvec;
  192. GetLidarObj(objvec,lidarobjvec);
  193. double timex = pc_ptr->header.stamp;
  194. timex = timex/1000.0;
  195. lidarobjvec.set_timestamp(pc_ptr->header.stamp);
  196. int ntlen;
  197. std::string out = lidarobjvec.SerializeAsString();
  198. // char * strout = lidarobjtostr(lidarobjvec,ntlen);
  199. iv::modulecomm::ModuleSendMsg(gpdetect,out.data(),out.length());
  200. // delete strout;
  201. // int i;
  202. // for(i=0;i<objvec.size();i++)
  203. // {
  204. // Obstacle x;
  205. // x = objvec.at(i);
  206. // std::cout<<"obj "<<i<<" x is "<<x.GetTypeString()<<std::endl;
  207. // iv::lidar::lidarobject y;
  208. // y = lidarobjvec.at(i);
  209. // std::cout<<" "<<" x is"<<y.position.x<<" y is "<<y.position.y<<" len x is "<<y.dimensions.x<<" len y is "<<y.dimensions.y<<std::endl;
  210. // std::cout<<" "<<" type is "<<y.mnType<<std::endl;
  211. // }
  212. }
  213. void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  214. {
  215. if(nSize <=16)return;
  216. unsigned int * pHeadSize = (unsigned int *)strdata;
  217. if(*pHeadSize > nSize)
  218. {
  219. std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
  220. }
  221. QTime xTime;
  222. xTime.start();
  223. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  224. new pcl::PointCloud<pcl::PointXYZI>());
  225. int nNameSize;
  226. nNameSize = *pHeadSize - 4-4-8;
  227. char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
  228. memcpy(strName,(char *)((char *)strdata +4),nNameSize);
  229. point_cloud->header.frame_id = strName;
  230. memcpy(&point_cloud->header.seq,(char *)strdata+4+nNameSize,4);
  231. memcpy(&point_cloud->header.stamp,(char *)strdata+4+nNameSize+4,8);
  232. int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
  233. int i;
  234. pcl::PointXYZI * p;
  235. p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
  236. for(i=0;i<nPCount;i++)
  237. {
  238. pcl::PointXYZI xp;
  239. // if((p->x<-30)||(p->x>30)||(p->y>50)||(p->y<-50))
  240. // {
  241. // }
  242. // else
  243. // {
  244. memcpy(&xp,p,sizeof(pcl::PointXYZI));
  245. xp.z = xp.z + (-1.0) ;
  246. point_cloud->push_back(xp);
  247. // }
  248. p++;
  249. // xp.x = p->x;
  250. // xp.y = p->y;
  251. // xp.z = p->z;
  252. // xp.intensity = p->intensity;
  253. // point_cloud->push_back(xp);
  254. // p++;
  255. }
  256. // std::cout<<"pcl time is "<<xTime.elapsed()<<std::endl;
  257. DectectOnePCD(point_cloud);
  258. std::cout<<"time is "<<(QDateTime::currentMSecsSinceEpoch() % 1000)<<" "<<xTime.elapsed()<<std::endl;
  259. }
  260. //LidarApolloInstanceSegmentation
  261. int main(int argc, char *argv[])
  262. {
  263. QCoreApplication a(argc, argv);
  264. gseg = new LidarApolloInstanceSegmentation();
  265. // test();
  266. QString strpath = QCoreApplication::applicationDirPath();
  267. if(argc < 2)
  268. strpath = strpath + "/detection_lidar_cnn_segmentation.xml";
  269. else
  270. strpath = argv[1];
  271. std::cout<<strpath.toStdString()<<std::endl;
  272. iv::xmlparam::Xmlparam xparam(strpath.toStdString());
  273. gstrinput = xparam.GetParam("input","lidarpc_center");
  274. gstroutput = xparam.GetParam("output","lidar_cnn_dectect");
  275. gpa = iv::modulecomm::RegisterRecv(gstrinput.data(),ListenPointCloud);
  276. gpdetect = iv::modulecomm::RegisterSend(gstroutput.data(),10000000,1);
  277. return a.exec();
  278. }