#include #include "perception_lidar_vv7.h" #include #include #include #include #include #include #include #include #include #include #include "modulecomm.h" #include "ivversion.h" #include "ivbacktrace.h" #include "perceptionoutput.h" #include #include #include #include "ivfault.h" #include "ivlog.h" static void * glidar_pc; static void * glidar_obs; static void * g_lidar_pc_floor; static void * g_lidar_pc_nofloor; static void * glidar_pc_p; static void * glidar_per; static void * gpafusion; iv::Ivfault *gfault = nullptr; iv::Ivlog *givlog = nullptr; static char gstr_sensorheight[256]; static char gstr_vehicleheight[256]; static char gstr_inputmemname[256]; static char gstr_outputmemname[256]; static char gstr_skipxmin[256]; static char gstr_skipxmax[256]; static char gstr_skipymin[256]; static char gstr_skipymax[256]; static int g_robosys = 10; //#define OUT_GROUND namespace iv { const int grx = 200, gry = 550, centerx = 100, centery = 50; const double gridwide = 0.2; struct ObstacleBasic { bool valid; float nomal_x; float nomal_y; float nomal_z; float speed_relative; float speed_x; float speed_y; float speed_z; float high; float low; int esr_ID; }; // typedef boost::shared_ptr> ObsLiDAR; // typedef boost::shared_ptr> ObsRadar; // typedef boost::shared_ptr> ObsCamera; // typedef boost::shared_ptr>ObsRadarPointer; struct Obs_grid { double high; double low; double obshight; double groundheight; int pointcount; int ob;//??????0?? ?1???2??? }; typedef Obs_grid LidarGrid; typedef Obs_grid* LidarGridPtr; // int xxxx; } static void writepctosm(pcl::PointCloud::Ptr & point_cloud,void * pasm) { 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())); unsigned int * pu32 = (unsigned int *)(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)); // std::cout<<"width = "<width<header.frame_id.size()) + 4+8+point_cloud->size() * sizeof(pcl::PointXYZI)); delete strOut; } static float SENSOR_HEIGHT = 1.9; static float VEHICLE_HEIGHT = 2.2; //static float local_max_slope_ = 10; //static float general_max_slope_ = 3; //static float concentric_divider_distance_ = 1.5; //static float min_height_threshold_ = 0.05; //static float reclass_distance_threshold_ = 10.0; static float GRID_SIZE = 2.0; static float SMALLGRID_SIZE = 0.2; static float Height_Thesh_Ratio = 0.1; static float General_Thresh_Ratio = 0.1; static float VEC_LEN = 200.0; static float HOR_LEN = 200.0; static float VEC_MIN = -100.0; static float HOR_MIN = -100.0; static int g_seq = 0; static float skip_xmin = -0.9; static float skip_ymin = -2.3; static float skip_xmax = 0.9; static float skip_ymax = 2.3; static void GridGetObs(pcl::PointCloud::Ptr & point_cloud,std::shared_ptr> lidar_obs) { // std::cout<<"enter gird obs"<::Ptr point_cloud_nofloor( new pcl::PointCloud()); pcl::PointCloud::Ptr point_cloud_floor( new pcl::PointCloud()); QDateTime dt = QDateTime::currentDateTime(); point_cloud_floor->header.frame_id = "velodyne"; point_cloud_floor->height = 1; point_cloud_floor->header.stamp = dt.currentMSecsSinceEpoch(); point_cloud_floor->width = 0; point_cloud_floor->header.seq =g_seq; point_cloud_nofloor->header.frame_id = "velodyne"; point_cloud_nofloor->height = 1; point_cloud_nofloor->header.stamp = dt.currentMSecsSinceEpoch(); point_cloud_nofloor->width = 0; point_cloud_nofloor->header.seq =g_seq; g_seq++; int i,j; for(i=0;i<(nVecSize+2);i++) { for(j=0;j<(nHorSize+2);j++) { floor_find[i*(nHorSize+2) +j] = false; } } for(i=0;isize();i++) { float x = point_cloud->at(i).x; float y = point_cloud->at(i).y; float z = point_cloud->at(i).z; if((x>=skip_xmin)&&(y>=skip_ymin)&&(x<=skip_xmax)&&(y<=skip_ymax)) { continue; } float dis = sqrt(x*x + y*y); // if((dis>0.9)&&(z>(-SENSOR_HEIGHT-dis*General_Thresh_Ratio))&&(z<(-SENSOR_HEIGHT+dis*General_Thresh_Ratio))) if((z>(-SENSOR_HEIGHT-dis*General_Thresh_Ratio))&&(z<(-SENSOR_HEIGHT+dis*General_Thresh_Ratio))) { int Rpos,Cpos; Rpos = (y-VEC_MIN)/GRID_SIZE; Cpos = (x-HOR_MIN)/GRID_SIZE; if((Rpos>=0)&&(Rpos=0)&&(Cpossize();i++) { pcl::PointXYZI po = point_cloud->at(i); float x = point_cloud->at(i).x; float y = point_cloud->at(i).y; float z = point_cloud->at(i).z; if((x>=skip_xmin)&&(y>=skip_ymin)&&(x<=skip_xmax)&&(y<=skip_ymax)) { continue; } // float dis = sqrt(x*x + y*y); int Rpos,Cpos; Rpos = (y-VEC_MIN)/GRID_SIZE; Cpos = (x-HOR_MIN)/GRID_SIZE; if((Rpos>=0)&&(Rpos=0)&&(Cpos0.15) { point_cloud_nofloor->push_back(po); ++point_cloud_nofloor->width; } else { point_cloud_floor->push_back(po); ++point_cloud_floor->width; } } } //#endif // for(i=0;ipointcount = 0; int Rpos,Cpos; Rpos = (i*SMALLGRID_SIZE)/GRID_SIZE; Cpos = (j*SMALLGRID_SIZE)/GRID_SIZE; if((Rpos>=0)&&(Rpos=0)&&(Cposgroundheight = floor_h[xPos]; } else { p->groundheight = -SENSOR_HEIGHT+1000; } p->low = -SENSOR_HEIGHT+1000; p->high = -SENSOR_HEIGHT - 1000; p->obshight = 0; p->ob = 0; } } for(i=0;isize();i++) { pcl::PointXYZI pxyzi = point_cloud_nofloor->at(i); int x,y; x = (int)((pxyzi.y-VEC_MIN)/SMALLGRID_SIZE); y = (int)((pxyzi.x-HOR_MIN)/SMALLGRID_SIZE); if((x>=0)&&(x=0)) { iv::LidarGrid * p = pobsgrid + x*NXC+y; p->ob++; if(pxyzi.zlow)p->low = pxyzi.z; if(pxyzi.z>p->high)p->high = pxyzi.z; } } for(i=0;iob>=3) { if(p->low>(p->groundheight+VEHICLE_HEIGHT)) { // std::cout<<"low high"<low; temp.high = p->high; temp.nomal_z = p->high-p->low; temp.nomal_x = j*SMALLGRID_SIZE + 0.1+HOR_MIN; temp.nomal_y = i*SMALLGRID_SIZE +0.1 +VEC_MIN; lidar_obs->push_back(temp); } } } } delete pobsgrid; delete floor_find; delete floor_h_raw; delete floor_h; } #include #include "fusionobjectarray.pb.h" iv::fusion::fusionobjectarray xfusion; void ShareFusionObject(void * pa ,std::shared_ptr> & lidar_obs) { double timestamp = std::chrono::system_clock::now().time_since_epoch().count(); timestamp = timestamp/1000000.0; xfusion.clear_obj(); xfusion.set_timestamp(timestamp); iv::fusion::fusionobject * pobj = xfusion.add_obj(); pobj->set_id(0); pobj->set_type(0); iv::fusion::VelXY *pxvel = new iv::fusion::VelXY; pxvel->set_x(0); pxvel->set_y(0); pobj->set_allocated_vel_abs(pxvel); iv::fusion::Dimension * pxdim = new iv::fusion::Dimension; pxdim->set_x(0.2); pxdim->set_y(0.2); pxdim->set_z(2.0); pobj->set_allocated_dimensions(pxdim); int i; int nsize = lidar_obs->size(); for(i=0;iadd_nomal_centroid(); pcen->set_nomal_x(lidar_obs->at(i).nomal_x); pcen->set_nomal_y(lidar_obs->at(i).nomal_y); pcen->set_nomal_z(lidar_obs->at(i).nomal_z); } int nbytesize = xfusion.ByteSize(); std::shared_ptr pstr_ptr = std::shared_ptr(new char[nbytesize]); if(xfusion.SerializeToArray(pstr_ptr.get(),nbytesize)) { iv::modulecomm::ModuleSendMsg(pa,pstr_ptr.get(),nbytesize); } else { std::cout<<" serialzie fusion fail."< nSize) { std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<::Ptr point_cloud( new pcl::PointCloud()); 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;ix; xp.y = p->y; xp.z = p->z; xp.intensity = p->intensity; point_cloud->push_back(xp); p++; } std::shared_ptr> lidar_obs(new std::vector); GridGetObs(point_cloud,lidar_obs); // perception_lidar_vv7_ProcObs(point_cloud,lidar_obs); // std::cout<<"prc."<size() == 0) { iv::ObstacleBasic temp; temp.low = 0; temp.high = 3.0; temp.nomal_z = 3.0; temp.nomal_x = 1000; temp.nomal_y = 1000; lidar_obs->push_back(temp); } if(lidar_obs->size() >0)iv::modulecomm::ModuleSendMsg(glidar_obs,(char *)(lidar_obs->data()),lidar_obs->size()*sizeof(iv::ObstacleBasic)); } else { g_robosys--; if(g_robosys<0) { g_robosys = 0; } } gfault->SetFaultState(0, 0, "ok"); // return; // gw->UpdatePointCloud(point_cloud); } void PERCEPTION_LIDAR_VV7SHARED_EXPORT StartPerception_lidar_vv7() { std::cout<<"HHINow Start LIDAR Perception"<verbose("load yaml error."); return; } if(config["SensorHeight"]) { strncpy(gstr_sensorheight,config["SensorHeight"].as().data(),255); } if(config["VehicleHeight"]) { strncpy(gstr_vehicleheight,config["VehicleHeight"].as().data(),255); } if(config["inputmemname"]) { strncpy(gstr_inputmemname,config["inputmemname"].as().data(),255); } if(config["outputmemname"]) { strncpy(gstr_outputmemname,config["outputmemname"].as().data(),255); } if(config["skip_xmin"]) { strncpy(gstr_skipxmin,config["skip_xmin"].as().data(),255); } if(config["skip_xmax"]) { strncpy(gstr_skipxmax,config["skip_xmax"].as().data(),255); } if(config["skip_ymin"]) { strncpy(gstr_skipymin,config["skip_ymin"].as().data(),255); } if(config["skip_ymax"]) { strncpy(gstr_skipymax,config["skip_ymax"].as().data(),255); } // std::cout<-r /* struct option { const char * name; // 参数的名称 int has_arg; // 是否带参数值,有三种:no_argument, required_argument,optional_argument int * flag; // 为空时,函数直接将 val 的数值从getopt_long的返回值返回出去, // 当非空时,val的值会被赋到 flag 指向的整型数中,而函数返回值为0 int val; // 用于指定函数找到该选项时的返回值,或者当flag非空时指定flag指向的数据的值 }; 其中: no_argument(即0),表明这个长参数不带参数(即不带数值,如:--name) required_argument(即1),表明这个长参数必须带参数(即必须带数值,如:--name Bob) optional_argument(即2),表明这个长参数后面带的参数是可选的,(即--name和--name Bob均可) */ static struct option long_options[] = { {"setyaml", required_argument, NULL, 's'}, {"help", no_argument, NULL, 'h'}, // {"optarg", optional_argument, NULL, 'o'}, {0, 0, 0, 0} // 添加 {0, 0, 0, 0} 是为了防止输入空值 }; while ( (opt = getopt_long(argc, argv, optstring, long_options, &option_index)) != -1) { // printf("opt = %c\n", opt); // 命令参数,亦即 -a -b -n -r // printf("optarg = %s\n", optarg); // 参数内容 // printf("optind = %d\n", optind); // 下一个被处理的下标值 // printf("argv[optind - 1] = %s\n", argv[optind - 1]); // 参数内容 // printf("option_index = %d\n", option_index); // 当前打印参数的下标值 // printf("\n"); switch(opt) { case 's': strncpy(gstr_yaml,optarg,255); break; case 'h': print_useage(); nRtn = 1; //because use -h break; default: break; } } return nRtn; } int main(int argc, char *argv[]) { RegisterIVBackTrace(); showversion("detection_lidar_grid"); QCoreApplication a(argc, argv); gfault = new iv::Ivfault("lidar_grid"); givlog = new iv::Ivlog("lidar_grid"); snprintf(gstr_yaml,255,""); int nRtn = GetOptLong(argc,argv); if(nRtn == 1) //show help,so exit. { return 0; } snprintf(gstr_sensorheight,255,"2.0"); snprintf(gstr_vehicleheight,255,"2.3"); snprintf(gstr_inputmemname,255,"lidar_pc"); snprintf(gstr_outputmemname,255,"lidar_obs"); snprintf(gstr_skipxmin,255,"-0.9"); snprintf(gstr_skipxmax,255,"0.9"); snprintf(gstr_skipymin,255,"-2.3"); snprintf(gstr_skipymax,255,"2.3"); givlog->verbose("yaml is %s ",gstr_yaml); if(strnlen(gstr_yaml,255)>0) { decodeyaml(gstr_yaml); } SENSOR_HEIGHT = atof(gstr_sensorheight); VEHICLE_HEIGHT = atof(gstr_vehicleheight); skip_xmin = atof(gstr_skipxmin); skip_xmax = atof(gstr_skipxmax); skip_ymin = atof(gstr_skipymin); skip_ymax = atof(gstr_skipymax); StartPerception_lidar_vv7(); return a.exec(); }