|
@@ -0,0 +1,333 @@
|
|
|
+#include <QCoreApplication>
|
|
|
+#include <QDateTime>
|
|
|
+
|
|
|
+#include <pcl/common/io.h>
|
|
|
+
|
|
|
+
|
|
|
+#include <pcl/io/io.h>
|
|
|
+#include <pcl/io/pcd_io.h>
|
|
|
+//#include <pcl/filters/statistical_outlier_removal.h>
|
|
|
+#include <pcl/filters/radius_outlier_removal.h>
|
|
|
+
|
|
|
+#include <iostream>
|
|
|
+#include <fstream>
|
|
|
+#include <yaml-cpp/yaml.h>
|
|
|
+#include <QMutex>
|
|
|
+#include <vector>
|
|
|
+#include <thread>
|
|
|
+
|
|
|
+#include "lidarmerge.h"
|
|
|
+#include "modulecomm.h"
|
|
|
+#include "ivversion.h"
|
|
|
+
|
|
|
+
|
|
|
+QMutex gMutex;
|
|
|
+
|
|
|
+static qint64 glasttime = 0;
|
|
|
+static std::vector<iv::lidar_data> gvectorlidar;
|
|
|
+static char gstroutmemname[255];
|
|
|
+static void * gpaout;
|
|
|
+
|
|
|
+void dec_yaml(const char * stryamlpath)
|
|
|
+{
|
|
|
+
|
|
|
+ YAML::Node config;
|
|
|
+ try
|
|
|
+ {
|
|
|
+ config = YAML::LoadFile(stryamlpath);
|
|
|
+ }
|
|
|
+ catch(YAML::BadFile e)
|
|
|
+ {
|
|
|
+ qDebug("load error.");
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ int i;
|
|
|
+ int nlidarsize;
|
|
|
+ std::vector<std::string> veclidarname;
|
|
|
+
|
|
|
+ if(config["lidar"])
|
|
|
+ {
|
|
|
+ qDebug("have lidar size is %d",config["lidar"].size());
|
|
|
+ nlidarsize = config["lidar"].size();
|
|
|
+ for(i=0;i<nlidarsize;i++)
|
|
|
+ {
|
|
|
+ std::string strname = config["lidar"][i].as<std::string>();
|
|
|
+ veclidarname.push_back(strname);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ if(nlidarsize <1)return;
|
|
|
+
|
|
|
+ std::string strmemname;
|
|
|
+ std::string stroffset_x;
|
|
|
+ std::string stroffset_y;
|
|
|
+ std::string stroffset_z;
|
|
|
+ std::string stroffset_angle;
|
|
|
+ std::string strtem;
|
|
|
+
|
|
|
+ double fignore_xmax = 0;
|
|
|
+ double fignore_ymax = 0;
|
|
|
+ double fignore_xmin = 0;
|
|
|
+ double fignore_ymin = 0;
|
|
|
+ double fignore_zmax = 0;
|
|
|
+ double fignore_zmin = 0;
|
|
|
+
|
|
|
+ if(config["ignore"]["xmin"])
|
|
|
+ {
|
|
|
+ strtem = config["ignore"]["xmin"].as<std::string>();
|
|
|
+ fignore_xmin = atof(strtem.data());
|
|
|
+ }
|
|
|
+
|
|
|
+ if(config["ignore"]["ymin"])
|
|
|
+ {
|
|
|
+ strtem = config["ignore"]["ymin"].as<std::string>();
|
|
|
+ fignore_ymin = atof(strtem.data());
|
|
|
+ }
|
|
|
+
|
|
|
+ if(config["ignore"]["xmax"])
|
|
|
+ {
|
|
|
+ strtem = config["ignore"]["xmax"].as<std::string>();
|
|
|
+ fignore_xmax = atof(strtem.data());
|
|
|
+ }
|
|
|
+
|
|
|
+ if(config["ignore"]["ymax"])
|
|
|
+ {
|
|
|
+ strtem = config["ignore"]["ymax"].as<std::string>();
|
|
|
+ fignore_ymax = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config["ignore"]["zmax"])
|
|
|
+ {
|
|
|
+ strtem = config["ignore"]["zmax"].as<std::string>();
|
|
|
+ fignore_zmax = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config["ignore"]["zmin"])
|
|
|
+ {
|
|
|
+ strtem = config["ignore"]["zmin"].as<std::string>();
|
|
|
+ fignore_zmin = atof(strtem.data());
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ for(i=0;i<nlidarsize;i++)
|
|
|
+ {
|
|
|
+ if(config[veclidarname[i].data()])
|
|
|
+ {
|
|
|
+ if((config[veclidarname[i].data()]["memname"])&&(config[veclidarname[i].data()]["offset"]["x"])&&(config[veclidarname[i].data()]["offset"]["y"])&&(config[veclidarname[i].data()]["offset"]["z"]))
|
|
|
+ {
|
|
|
+ strmemname = config[veclidarname[i].data()]["memname"].as<std::string>();
|
|
|
+ stroffset_x = config[veclidarname[i].data()]["offset"]["x"].as<std::string>();
|
|
|
+ stroffset_y = config[veclidarname[i].data()]["offset"]["y"].as<std::string>();
|
|
|
+ stroffset_z = config[veclidarname[i].data()]["offset"]["z"].as<std::string>();
|
|
|
+ stroffset_angle = config[veclidarname[i].data()]["offset"]["angle"].as<std::string>();
|
|
|
+
|
|
|
+ iv::lidar_data xlidardata;
|
|
|
+ xlidardata.foff_x = atof(stroffset_x.data());
|
|
|
+ xlidardata.foff_y = atof(stroffset_y.data());
|
|
|
+ xlidardata.foff_z = atof(stroffset_z.data());
|
|
|
+ xlidardata.foff_angle = atof(stroffset_angle.data());
|
|
|
+ if(config[veclidarname[i].data()]["maximum"]["x"])
|
|
|
+ {
|
|
|
+ strtem = config[veclidarname[i].data()]["maximum"]["x"].as<std::string>();
|
|
|
+ xlidardata.fmax_x = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config[veclidarname[i].data()]["maximum"]["y"])
|
|
|
+ {
|
|
|
+ strtem = config[veclidarname[i].data()]["maximum"]["y"].as<std::string>();
|
|
|
+ xlidardata.fmax_y = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config[veclidarname[i].data()]["maximum"]["z"])
|
|
|
+ {
|
|
|
+ strtem = config[veclidarname[i].data()]["maximum"]["z"].as<std::string>();
|
|
|
+ xlidardata.fmax_z = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config[veclidarname[i].data()]["minimum"]["x"])
|
|
|
+ {
|
|
|
+ strtem = config[veclidarname[i].data()]["minimum"]["x"].as<std::string>();
|
|
|
+ xlidardata.fmin_x = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config[veclidarname[i].data()]["minimum"]["y"])
|
|
|
+ {
|
|
|
+ strtem = config[veclidarname[i].data()]["minimum"]["y"].as<std::string>();
|
|
|
+ xlidardata.fmin_y = atof(strtem.data());
|
|
|
+ }
|
|
|
+ if(config[veclidarname[i].data()]["minimum"]["z"])
|
|
|
+ {
|
|
|
+ strtem = config[veclidarname[i].data()]["minimum"]["z"].as<std::string>();
|
|
|
+ xlidardata.fmin_z = atof(strtem.data());
|
|
|
+ }
|
|
|
+
|
|
|
+ xlidardata.fignore_xmax = fignore_xmax;
|
|
|
+ xlidardata.fignore_ymax = fignore_ymax;
|
|
|
+ xlidardata.fignore_xmin = fignore_xmin;
|
|
|
+ xlidardata.fignore_ymin = fignore_ymin;
|
|
|
+ xlidardata.fignore_zmax = fignore_zmax;
|
|
|
+ xlidardata.fignore_zmin = fignore_zmin;
|
|
|
+
|
|
|
+
|
|
|
+ strncpy(xlidardata.strmemname,strmemname.data(),255);
|
|
|
+ gvectorlidar.push_back(xlidardata);
|
|
|
+ qDebug("name is %s ",strmemname.data());
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ if(config["output"])
|
|
|
+ {
|
|
|
+ strncpy(gstroutmemname,config["output"].as<std::string>().data(),255);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ strncpy(gstroutmemname,"lidar_pc",255);
|
|
|
+ }
|
|
|
+ return;
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+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;
|
|
|
+ }
|
|
|
+
|
|
|
+ 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;
|
|
|
+ xp.x = p->x;
|
|
|
+ xp.y = p->y;
|
|
|
+ xp.z = p->z;
|
|
|
+ xp.intensity = p->intensity;
|
|
|
+ point_cloud->push_back(xp);
|
|
|
+ p++;
|
|
|
+
|
|
|
+ // std::cout<<" x is "<<xp.x<<" y is "<<xp.y<<std::endl;
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ for(i=0;i<gvectorlidar.size();i++)
|
|
|
+ {
|
|
|
+ if(strncmp(strmemname,gvectorlidar[i].strmemname,255) == 0)
|
|
|
+ {
|
|
|
+ gMutex.lock();
|
|
|
+ gvectorlidar[i].mpoint_cloud_old = gvectorlidar[i].mpoint_cloud;
|
|
|
+ gvectorlidar[i].mpoint_cloud = point_cloud;
|
|
|
+ gvectorlidar[i].mupdatetime = QDateTime::currentMSecsSinceEpoch();
|
|
|
+ gvectorlidar[i].bUpdate = true;
|
|
|
+ gMutex.unlock();
|
|
|
+ }
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+void sharepointcloud(pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud,void * pa)
|
|
|
+{
|
|
|
+ char * strOut = new char[4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI)];
|
|
|
+
|
|
|
+ int * pHeadSize = (int *)strOut;
|
|
|
+ *pHeadSize = 4 + point_cloud->header.frame_id.size()+4+8;
|
|
|
+ memcpy(strOut+4,point_cloud->header.frame_id.c_str(),point_cloud->header.frame_id.size());
|
|
|
+ pcl::uint32_t * pu32 = (pcl::uint32_t *)(strOut+4+sizeof(point_cloud->header.frame_id.size()));
|
|
|
+ *pu32 = point_cloud->header.seq;
|
|
|
+ memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
|
|
|
+ pcl::PointXYZI * p;
|
|
|
+ p = (pcl::PointXYZI *)(strOut +4+sizeof(point_cloud->header.frame_id.size()) + 4+8 );
|
|
|
+ memcpy(p,point_cloud->points.data(),point_cloud->width * sizeof(pcl::PointXYZI));
|
|
|
+
|
|
|
+ iv::modulecomm::ModuleSendMsg(pa,strOut,4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI));
|
|
|
+ delete strOut;
|
|
|
+}
|
|
|
+
|
|
|
+void merge()
|
|
|
+{
|
|
|
+ int i;
|
|
|
+ std::vector<iv::lidar_data> xvectorlidar;
|
|
|
+ pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
|
|
|
+ new pcl::PointCloud<pcl::PointXYZI>());
|
|
|
+
|
|
|
+ pcl::PointCloud<pcl::PointXYZI>::Ptr cloud_filtered(
|
|
|
+ new pcl::PointCloud<pcl::PointXYZI>());
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+ gMutex.lock();
|
|
|
+ xvectorlidar = gvectorlidar;
|
|
|
+ for(i=0;i<gvectorlidar.size();i++)
|
|
|
+ {
|
|
|
+ gvectorlidar[i].bUpdate = false;
|
|
|
+ }
|
|
|
+ gMutex.unlock();
|
|
|
+ point_cloud = mergefunc(xvectorlidar);
|
|
|
+ pcl::RadiusOutlierRemoval<pcl::PointXYZI> pcFilter;
|
|
|
+ pcFilter.setInputCloud(point_cloud);
|
|
|
+ pcFilter.setRadiusSearch(0.8);
|
|
|
+ pcFilter.setMinNeighborsInRadius(20);
|
|
|
+ pcFilter.filter(*cloud_filtered);
|
|
|
+ sharepointcloud(cloud_filtered,gpaout);
|
|
|
+}
|
|
|
+
|
|
|
+void mergethread()
|
|
|
+{
|
|
|
+ int i;
|
|
|
+ while(1)
|
|
|
+ {
|
|
|
+ std::this_thread::sleep_for(std::chrono::milliseconds(1));
|
|
|
+ bool bNOtAllOK = false;
|
|
|
+ for(i=0;i<gvectorlidar.size();i++)
|
|
|
+ {
|
|
|
+ if(!gvectorlidar[i].bUpdate)
|
|
|
+ {
|
|
|
+ bNOtAllOK = true;
|
|
|
+ break;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ if(((QDateTime::currentMSecsSinceEpoch() - glasttime)>=150) ||(bNOtAllOK == false))
|
|
|
+ {
|
|
|
+ merge();
|
|
|
+ qDebug("time is %ld",glasttime);
|
|
|
+ glasttime = QDateTime::currentMSecsSinceEpoch();
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+int main(int argc, char *argv[])
|
|
|
+{
|
|
|
+ showversion("fusion_pointcloud_bus");
|
|
|
+ QCoreApplication a(argc, argv);
|
|
|
+
|
|
|
+ dec_yaml("fusion_pointcloud_bus.yaml");
|
|
|
+
|
|
|
+ void * pa;
|
|
|
+ int i;
|
|
|
+ for(i=0;i<gvectorlidar.size();i++)
|
|
|
+ {
|
|
|
+ iv::modulecomm::RegisterRecv(gvectorlidar[i].strmemname,ListenPointCloud);
|
|
|
+ }
|
|
|
+ gpaout = iv::modulecomm::RegisterSend(gstroutmemname,20000000,1);
|
|
|
+
|
|
|
+ std::thread xthread(mergethread);
|
|
|
+
|
|
|
+ return a.exec();
|
|
|
+}
|