浏览代码

change driver_cloud_swap_server.

yuchuli 1 年之前
父节点
当前提交
bf4488ce02

+ 9 - 3
src/driver/driver_cloud_swap_server/main.cpp

@@ -1,5 +1,7 @@
 #include <QCoreApplication>
 
+#include <QDateTime>
+
 #include <iostream>
 #include <vector>
 
@@ -110,17 +112,19 @@ class CloudSwapServiceImpl final : public iv::CloudSwapStream::Service {
               std::shared_ptr<char> pdata_ptr = std::shared_ptr<char>(new char[ndatasize]);
               memcpy(pdata_ptr.get(),request.xdata().data(),ndatasize);
               gpswapserver->broadmsg(strobjnodeid,pdata_ptr,ndatasize,request.pingavg(),request.flatencyinstore());
+              std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<"receive data from: "<<strnodeid<<std::endl;
           }
           else
           {
-              std::cout<<"receive heartbeat from "<<strnodeid<<std::endl;
+              std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<"receive heartbeat from "<<strnodeid<<std::endl;
           }
 
 
       }
+      if(pswap == NULL)return Status::OK;
       pswap->stopswap();  //Because connection fail.
-      std::cout<<" no conn"<<std::endl;
-      std::cout<<"dis connect."<<std::endl;
+      std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<" no conn"<<std::endl;
+      std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<"dis connect."<<std::endl;
 
     return Status::OK;
   }
@@ -433,6 +437,8 @@ int main(int argc, char *argv[])
 
 //    *p = 1;
 
+    std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<std::endl;
+
     snprintf(gstrport,255,"50061");
 
     int nRtn = GetOptLong(argc,argv);

+ 6 - 3
src/driver/driver_cloud_swap_server/swapunit.cpp

@@ -1,5 +1,7 @@
 #include "swapunit.h"
 
+#include <QDateTime>
+
 swapunit::swapunit(std::string strnodeid,std::string strobjnodeid,::grpc::ServerReaderWriter<iv::CloudSwapReplyStream, iv::CloudSwapRequestStream>* stream)
 {
     mstrnodeid = strnodeid;
@@ -33,7 +35,7 @@ int swapunit::sendmsg(std::string strobjid, std::shared_ptr<char> pdata_ptr, int
 
     if(mvectorsendmsgbuf.size()>30000)
     {
-        std::cout<<"may connection down, buffer now full."<<std::endl;
+        std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<"may connection down, buffer now full."<<std::endl;
         mmutex.lock();
         mvectorsendmsgbuf.clear();
         mmutex.unlock();
@@ -102,7 +104,7 @@ void swapunit::threadsend(::grpc::ServerReaderWriter<iv::CloudSwapReplyStream, i
 
         for(i=0;i<nsize;i++)
         {
-            std::cout<<" add reply data. "<<std::endl;
+            std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<" add reply data. "<<std::endl;
             xreply.add_xdata(xvectorsendmsgbuf[i].pdata_ptr.get(),xvectorsendmsgbuf[i].ndatasize);
         }
         xreply.set_flatencyinstore_obj(flatencyinnodestore);
@@ -110,7 +112,7 @@ void swapunit::threadsend(::grpc::ServerReaderWriter<iv::CloudSwapReplyStream, i
         xreply.set_flatency_inobjnode(fpinginobj);
         xreply.set_nmsgservertime(xNow);
  //       xreply.set_nres(1);
-        std::cout<<mstrnodeid<<" reply data size : "<<xreply.xdata_size()<<std::endl;
+        std::cout<<QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz:").toStdString()<<mstrnodeid<<" reply data size : "<<xreply.xdata_size()<<std::endl;
         stream->Write(xreply);
 
         xLastSend = xNow;
@@ -127,6 +129,7 @@ bool swapunit::CanDel()
 void swapunit::stopswap()
 {
     mbrun = false;
+    mpthread->join();
 }
 
 void swapunit::SetPingAvg(double fpingavg)

+ 51 - 0
src/fusion/fusion_pointcloud_shenlan/fusion_pointcloud_shenlan.pro

@@ -0,0 +1,51 @@
+QT -= gui
+
+CONFIG += c++14 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which as been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+QMAKE_LFLAGS += -no-pie
+
+# You can also make your code fail to compile if you use deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += main.cpp \
+    lidarmerge.cpp
+
+INCLUDEPATH += /usr/include/pcl-1.7
+INCLUDEPATH += /usr/include/pcl-1.8
+INCLUDEPATH += /usr/include/eigen3
+
+LIBS += /usr/lib/aarch64-linux-gnu/libpcl_*.so
+
+HEADERS += \
+    lidarmerge.h
+
+
+unix:LIBS += -lboost_thread -lboost_system
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+!include(../../../include/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}
+
+!include(../../../include/ivboost.pri ) {
+    error( "Couldn't find the ivboost.pri file!" )
+}
+
+!include(../../../include/ivyaml-cpp.pri ) {
+    error( "Couldn't find the ivyaml-cpp.pri file!" )
+}
+
+!include(../../../include/ivpcl.pri ) {
+    error( "Couldn't find the ivpcl.pri file!" )
+}

+ 27 - 0
src/fusion/fusion_pointcloud_shenlan/fusion_pointcloud_shenlan.yaml

@@ -0,0 +1,27 @@
+lidar:
+  - left
+  - right
+  - center
+left:
+  memname: lidarpc_left
+  maximum:
+    x: 100
+    y: 100.0
+    z: 100
+  minimum:
+    x: -100
+    y: -100.0
+    z: -100
+right:
+  memname: lidarpc_right
+  maximum:
+    x: 100
+    y: 100.0
+    z: 100
+  minimum:
+    x: -100
+    y: -100.0
+    z: -100
+center:
+  memname: lidar_pc
+output: lidarpc_fusion

+ 74 - 0
src/fusion/fusion_pointcloud_shenlan/lidarmerge.cpp

@@ -0,0 +1,74 @@
+#include "lidarmerge.h"
+
+#include <QDateTime>
+
+#include <QMutex>
+
+extern QMutex gMutex;
+
+static int g_seq = 0;
+
+pcl::PointCloud<pcl::PointXYZI>::Ptr mergefunc(std::vector<iv::lidar_data> xvectorlidar)
+{
+    pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
+                new pcl::PointCloud<pcl::PointXYZI>());
+
+    point_cloud->header.frame_id = "velodyne";
+    point_cloud->height = 1;
+    point_cloud->header.stamp = QDateTime::currentMSecsSinceEpoch();
+    point_cloud->width = 0;
+    point_cloud->header.seq =g_seq;
+    g_seq++;
+
+
+    int i,j;
+    for(i=0;i<xvectorlidar.size();i++)
+    {
+        int nsize;
+
+        pcl::PointCloud<pcl::PointXYZI>::Ptr partpoint_cloud;
+        int64_t curtime = QDateTime::currentMSecsSinceEpoch();
+        if((xvectorlidar[i].bUpdate)||((curtime -xvectorlidar[i].mupdatetime)<150))
+        {
+            gMutex.lock();
+            partpoint_cloud = xvectorlidar[i].mpoint_cloud;
+            gMutex.unlock();
+            nsize = partpoint_cloud->width;
+            qDebug("size is %d ",nsize);
+
+            for(j=0;j<nsize;j++)
+            {
+                pcl::PointXYZI point;
+                point = partpoint_cloud->at(j);
+                point.x = (point.x + xvectorlidar[i].foff_x)*cos(xvectorlidar[i].foff_angle) -(point.y + xvectorlidar[i].foff_y)*sin(xvectorlidar[i].foff_angle) ;
+                point.y = (point.y + xvectorlidar[i].foff_y)*cos(xvectorlidar[i].foff_angle) + (point.x + xvectorlidar[i].foff_x)*sin(xvectorlidar[i].foff_angle);
+                point.z = point.z + xvectorlidar[i].foff_z;
+
+                if(point.x>xvectorlidar[i].fmax_x)continue;
+                if(point.y>xvectorlidar[i].fmax_y)continue;
+                if(point.z>xvectorlidar[i].fmax_z)continue;
+                if(point.z > xvectorlidar[i].fignore_zmax) continue;
+                if(point.z < xvectorlidar[i].fignore_zmin) continue;
+//                std::cout<<"  fignore  zmin  "<<xvectorlidar[i].fignore_zmin<<std::endl;
+
+                if(point.x<xvectorlidar[i].fmin_x)continue;
+                if(point.y<xvectorlidar[i].fmin_y)continue;
+                if(point.z<xvectorlidar[i].fmin_z)continue;
+
+                if((point.x>xvectorlidar[i].fignore_xmin)&&(point.x<xvectorlidar[i].fignore_xmax)&&(point.y>xvectorlidar[i].fignore_ymin)&&(point.y<xvectorlidar[i].fignore_ymax))
+                {
+                    continue;
+                }
+                if(!pcl_isfinite(point.x)||!pcl_isfinite(point.y)||!pcl_isfinite(point.z)||!pcl_isfinite(point.intensity)) continue;
+
+                point_cloud->push_back(point);
+                ++point_cloud->width;
+            }
+
+
+        }
+    }
+    qDebug("merge size is %d ",point_cloud->width);
+
+    return point_cloud;
+}

+ 40 - 0
src/fusion/fusion_pointcloud_shenlan/lidarmerge.h

@@ -0,0 +1,40 @@
+#ifndef LIDARMERGE_H
+#define LIDARMERGE_H
+
+#include <pcl/common/io.h>
+
+#include <pcl/io/io.h>
+#include <pcl/io/pcd_io.h>
+
+
+
+namespace  iv {
+struct lidar_data
+{
+    char strmemname[256];
+    double foff_x = 0.0;
+    double foff_y = 0.0;
+    double foff_z = 0.0;
+    double foff_angle = 0.0;
+    bool bUpdate = false;
+    double fmax_x = 0;
+    double fmax_y = 0;
+    double fmax_z = 0;
+    double fmin_x = 0;
+    double fmin_y = 0;
+    double fmin_z = 0;
+    double fignore_xmax = 0;
+    double fignore_ymax = 0;
+    double fignore_xmin = 0;
+    double fignore_ymin = 0;
+    double fignore_zmax = 0;
+    double fignore_zmin = 0;
+    pcl::PointCloud<pcl::PointXYZI>::Ptr mpoint_cloud = NULL;
+    int64_t mupdatetime = 0;
+    pcl::PointCloud<pcl::PointXYZI>::Ptr mpoint_cloud_old = NULL;
+};
+
+}
+
+pcl::PointCloud<pcl::PointXYZI>::Ptr mergefunc(std::vector<iv::lidar_data> xvectorlidar);
+#endif // LIDARMERGE_H

+ 333 - 0
src/fusion/fusion_pointcloud_shenlan/main.cpp

@@ -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();
+}

+ 6 - 0
src/tool/bqev_multilidarcalib/bqev_multilidarcalib.pro

@@ -11,6 +11,8 @@ greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
 TARGET = bqev_multilidarcalib
 TEMPLATE = app
 
+CONFIG += c++14
+
 
 # The following define makes your compiler emit warnings if you use
 # any feature of Qt which has been marked as deprecated (the exact warnings
@@ -106,6 +108,10 @@ INCLUDEPATH += /usr/include/eigen3
     error( "Couldn't find the ivopencv.pri file!" )
 }
 
+!include(../../../include/ivpcl.pri ) {
+    error( "Couldn't find the ivpcl.pri file!" )
+}
+
 !include(../../../include/ivyaml-cpp.pri ) {
     error( "Couldn't find the ivyaml-cpp.pri file!" )
 }

+ 6 - 2
src/tool/bqev_multilidarcalib/ndt_calib.cpp

@@ -1,10 +1,14 @@
 #include <tf/transform_broadcaster.h>
 #include <tf/transform_datatypes.h>
 
+
+#include <numeric>
+
+#include <pcl/common/io.h>
 #include <pcl/io/io.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/point_types.h>
-#include <pcl_conversions/pcl_conversions.h>
+//#include <pcl_conversions/pcl_conversions.h>
 
 #include <ndt_cpu/NormalDistributionsTransform.h>
 #include <pcl/registration/ndt.h>
@@ -226,7 +230,7 @@ void point_ndtcalib(pcl::PointCloud<pcl::PointXYZI>::Ptr raw_scan1,pcl::PointClo
       *merge_pc = *transformed_scan_ptr2 + *scan_ptr1;
       t_calib = t_localizer;
 
-      pcl::io::savePCDFile("/home/nvidia/app/app/merge.pcd",*merge_pc);
+ //     pcl::io::savePCDFile("/home/nvidia/app/app/merge.pcd",*merge_pc);