#include #include #include #include #include #include #include #include "math.h" #include #include //#include //"the format of " << limitPath << " is not correct, use default data" #include "modulecomm.h" #include "lidar_driver_rs16.h" #include "lidar_rs16_rawdata.h" #ifdef VV7_1 int vv7; #endif #define Lidar_Pi 3.1415926535897932384626433832795 #define Lidar32 (unsigned long)3405883584//192.168.1.203 #define Lidar_roll_ang (90)*Lidar_Pi/180.0 std::thread * g_prs16Thread; std::thread * g_prs16ProcThread; void * g_rs16_raw; void * g_lidar_pc; bool g_brs16_run = false; bool g_brs16_running = false; bool g_brs16_Proc_running = false; int g_seq = 0; extern char gstr_memname[256]; extern char gstr_rollang[256]; extern char gstr_inclinationang_yaxis[256]; //from y axis extern char gstr_inclinationang_xaxis[256]; //from x axis extern char gstr_hostip[256]; extern char gstr_port[256]; class rs16_Buf { private: char * mstrdata; int mnSize; //Data SizeUse QMutex mMutex; int mIndex; public: rs16_Buf() { mstrdata = new char[BK32_DATA_BUFSIZE]; mIndex = 0; mnSize = 0; } ~rs16_Buf() { delete mstrdata; } void WriteData(const char * strdata,const int nSize) { mMutex.lock(); memcpy(mstrdata,strdata,nSize); mnSize = nSize; mIndex++; mMutex.unlock(); } int ReadData(char * strdata,const int nRead,int * pnIndex) { int nRtn = 0; if(mnSize <= 0)return 0; mMutex.lock(); nRtn = mnSize; if(nRtn >nRead) { nRtn = nRead; std::cout<<"lidar_rs16 rs16_Buf ReadData data nRead = "< QTime gTime; void processrs16_Data(QByteArray ba) { gnPac++; unsigned short * pAng; float fAng; char * pdata; float fa,fb; pdata = ba.data(); if(ba.length() == 1248) { std::cout<<"receive pac"<300) { gAngle_Total = gAngle_Total + fabs(fabs(fAng-gAngle_Old)-360); } else { gAngle_Total = gAngle_Total + fabs(fabs(fAng-gAngle_Old)); } gAngle_Old = fAng; if(gAngle_Total > 360) { g_rs16_Buf->WriteData(g_RawData_Buf,gnRawPos); // lidar_rs16_raw * p = new lidar_rs16_raw(); // p->mnLen = gnRawPos; // memcpy(p->mstrdata,g_RawData_Buf,gnRawPos); // g_rs16_raw->writemsg((char *)p,sizeof(lidar_rs16_raw)); // delete p; memcpy(g_RawData_Buf,pdata+42,1206); gnRawPos = 1206; // std::cout<<"index = "<bind(QHostAddress(gstr_hostip), atoi(gstr_port)); // bool bbind = udpSocket->bind(QHostAddress("192.168.50.62"), 6699); // udpSocket->bind(6699); // bool bbind = udpSocket->bind(QHostAddress::Any, 6699); // bool bbind = udpSocket->bind( 6699); int i = 0; while(g_brs16_run) { if(udpSocket->hasPendingDatagrams()) { i++;std::cout<<"have data."<receiveDatagram(); processrs16_Data(datagram.data()); datagram.clear(); } else { // std::cout<<"running."<close(); delete udpSocket; g_brs16_running = false; std::cout<<"rs16_Func Exit."<::Ptr point_cloud( new pcl::PointCloud()); // point_cloud->header.stamp = // pcl_conversions::toPCL(sweep_data->header).stamp; point_cloud->header.frame_id = "velodyne"; point_cloud->height = 1; point_cloud->header.stamp = dt.currentMSecsSinceEpoch(); point_cloud->width = 0; point_cloud->header.seq =g_seq; g_seq++; unsigned char * pstr = (unsigned char *)strdata; // std::cout<<"enter obs."<points.push_back(point); ++point_cloud->width; } } wt = wt + 0.18; for (pointi = 0; pointi < 16; pointi++) { Ang = (0 - wt) / 180.0 * Lidar_Pi; // Ang = Ang+angdiff; Range = ((pstr[bag*1206 + Group * 100 + 52 + 3 * pointi] << 8) + pstr[bag*1206+Group * 100 + 53 + 3 * pointi]); unsigned char intensity = pstr[bag*1206 + Group * 100 + 54 + 3 * pointi]; Range=Range* 5.0/1000.0; if(Range<150) { pcl::PointXYZI point; point.x = Range*cos(V_theta[pointi] / 180 * Lidar_Pi)*cos(Ang + frollang); point.y = Range*cos(V_theta[pointi] / 180 * Lidar_Pi)*sin(Ang + frollang); point.z = Range*sin(V_theta[pointi] / 180 * Lidar_Pi); if(binclix) { double y,z; y = point.y;z = point.z; point.y = y*cos_finclinationang_xaxis +z*sin_finclinationang_xaxis; point.z = z*cos_finclinationang_xaxis - y*sin_finclinationang_xaxis; } if(bincliy) { double z,x; z = point.z;x = point.x; point.z = z*cos_finclinationang_yaxis + x*sin_finclinationang_yaxis; point.x = x*cos_finclinationang_yaxis - z*sin_finclinationang_yaxis; } point.intensity = intensity; point_cloud->points.push_back(point); ++point_cloud->width; } } } } 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(g_lidar_pc,strOut,4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI)); delete strOut; // std::cout<<"point cloud width = "<width<<" size = "<size()<ReadData(strdata,BK32_DATA_BUFSIZE,&nIndex))>0) { //process data. process_rs16obs(strdata,nRead); } else { // std::cout<<"running."<join(); g_prs16ProcThread->join(); delete g_prs16ProcThread; delete g_prs16Thread; delete g_rs16_Buf; delete g_RawData_Buf; }