|
@@ -6,6 +6,12 @@
|
|
|
#include <lidar_centerpoint/centerpoint_trt.hpp>
|
|
|
#include <lidar_centerpoint/preprocess/pointcloud_densification.hpp>
|
|
|
|
|
|
+
|
|
|
+#include "modulecomm.h"
|
|
|
+
|
|
|
+void * gpa;
|
|
|
+void * gpdetect;
|
|
|
+
|
|
|
using namespace centerpoint;
|
|
|
|
|
|
std::unique_ptr<CenterPointTRT> detector_ptr_{nullptr};
|
|
@@ -50,10 +56,71 @@ void init()
|
|
|
|
|
|
}
|
|
|
|
|
|
+void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
|
|
|
+{
|
|
|
+ if(nSize <=16)return;
|
|
|
+ unsigned int * pHeadSize = (unsigned int *)strdata;
|
|
|
+ if(*pHeadSize > nSize)
|
|
|
+ {
|
|
|
+ std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
|
|
|
+ }
|
|
|
+
|
|
|
+ QTime xTime;
|
|
|
+ xTime.start();
|
|
|
+
|
|
|
+ pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
|
|
|
+ new pcl::PointCloud<pcl::PointXYZI>());
|
|
|
+ int nNameSize;
|
|
|
+ nNameSize = *pHeadSize - 4-4-8;
|
|
|
+ char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
|
|
|
+ memcpy(strName,(char *)((char *)strdata +4),nNameSize);
|
|
|
+ point_cloud->header.frame_id = strName;
|
|
|
+ memcpy(&point_cloud->header.seq,(char *)strdata+4+nNameSize,4);
|
|
|
+ memcpy(&point_cloud->header.stamp,(char *)strdata+4+nNameSize+4,8);
|
|
|
+ int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
|
|
|
+ int i;
|
|
|
+ pcl::PointXYZI * p;
|
|
|
+ p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
|
|
|
+ for(i=0;i<nPCount;i++)
|
|
|
+ {
|
|
|
+ pcl::PointXYZI xp;
|
|
|
+// if((p->x<-30)||(p->x>30)||(p->y>50)||(p->y<-50))
|
|
|
+// {
|
|
|
+
|
|
|
+// }
|
|
|
+// else
|
|
|
+// {
|
|
|
+ memcpy(&xp,p,sizeof(pcl::PointXYZI));
|
|
|
+ xp.z = xp.z;
|
|
|
+ point_cloud->push_back(xp);
|
|
|
+
|
|
|
+// }
|
|
|
+ p++;
|
|
|
+// xp.x = p->x;
|
|
|
+// xp.y = p->y;
|
|
|
+// xp.z = p->z;
|
|
|
+// xp.intensity = p->intensity;
|
|
|
+// point_cloud->push_back(xp);
|
|
|
+// p++;
|
|
|
+ }
|
|
|
+
|
|
|
+// std::cout<<"pcl time is "<<xTime.elapsed()<<std::endl;
|
|
|
+
|
|
|
+
|
|
|
+ std::vector<Box3D> det_boxes3d;
|
|
|
+ detector_ptr_ ->detect(point_cloud,det_boxes3d);
|
|
|
+ std::cout<<" box size: "<<det_boxes3d.size()<<std::endl;
|
|
|
+
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
int main(int argc, char *argv[])
|
|
|
{
|
|
|
QCoreApplication a(argc, argv);
|
|
|
init();
|
|
|
|
|
|
+ gpa = iv::modulecomm::RegisterRecv("lidarpc_center",ListenPointCloud);
|
|
|
+
|
|
|
return a.exec();
|
|
|
}
|