perception_lidar_vv7.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683
  1. #include <QCoreApplication>
  2. #include "perception_lidar_vv7.h"
  3. #include <getopt.h>
  4. #include <thread>
  5. #include <vector>
  6. #include <list>
  7. #include <iostream>
  8. #include <QDateTime>
  9. #include <QMutex>
  10. #include <pcl/conversions.h>
  11. #include <pcl/point_cloud.h>
  12. #include <pcl/point_types.h>
  13. #include "modulecomm.h"
  14. #include "ivversion.h"
  15. #include "ivbacktrace.h"
  16. #include "perceptionoutput.h"
  17. #include <iostream>
  18. #include <fstream>
  19. #include <yaml-cpp/yaml.h>
  20. #include "ivfault.h"
  21. #include "ivlog.h"
  22. static void * glidar_pc;
  23. static void * glidar_obs;
  24. static void * g_lidar_pc_floor;
  25. static void * g_lidar_pc_nofloor;
  26. static void * glidar_pc_p;
  27. static void * glidar_per;
  28. iv::Ivfault *gfault = nullptr;
  29. iv::Ivlog *givlog = nullptr;
  30. static char gstr_sensorheight[256];
  31. static char gstr_vehicleheight[256];
  32. static char gstr_inputmemname[256];
  33. static char gstr_outputmemname[256];
  34. static char gstr_skipxmin[256];
  35. static char gstr_skipxmax[256];
  36. static char gstr_skipymin[256];
  37. static char gstr_skipymax[256];
  38. static int g_robosys = 10;
  39. //#define OUT_GROUND
  40. namespace iv {
  41. const int grx = 200, gry = 550, centerx = 100, centery = 50;
  42. const double gridwide = 0.2;
  43. struct ObstacleBasic
  44. {
  45. bool valid;
  46. float nomal_x;
  47. float nomal_y;
  48. float nomal_z;
  49. float speed_relative;
  50. float speed_x;
  51. float speed_y;
  52. float speed_z;
  53. float high;
  54. float low;
  55. int esr_ID;
  56. };
  57. // typedef boost::shared_ptr<std::vector<iv::ObstacleBasic>> ObsLiDAR;
  58. // typedef boost::shared_ptr<std::vector<iv::ObstacleBasic>> ObsRadar;
  59. // typedef boost::shared_ptr<std::vector<iv::ObstacleBasic>> ObsCamera;
  60. // typedef boost::shared_ptr<std::vector<iv::ObstacleBasic>>ObsRadarPointer;
  61. struct Obs_grid
  62. {
  63. double high;
  64. double low;
  65. double obshight;
  66. double groundheight;
  67. int pointcount;
  68. int ob;//??????0?? ?1???2???
  69. };
  70. typedef Obs_grid LidarGrid;
  71. typedef Obs_grid* LidarGridPtr;
  72. // int xxxx;
  73. }
  74. static void writepctosm(pcl::PointCloud<pcl::PointXYZI>::Ptr & point_cloud,void * pasm)
  75. {
  76. char * strOut = new char[4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI)];
  77. int * pHeadSize = (int *)strOut;
  78. *pHeadSize = 4 + point_cloud->header.frame_id.size()+4+8;
  79. memcpy(strOut+4,point_cloud->header.frame_id.c_str(),point_cloud->header.frame_id.size());
  80. pcl::uint32_t * pu32 = (pcl::uint32_t *)(strOut+4+sizeof(point_cloud->header.frame_id.size()));
  81. *pu32 = point_cloud->header.seq;
  82. memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
  83. pcl::PointXYZI * p;
  84. p = (pcl::PointXYZI *)(strOut +4+sizeof(point_cloud->header.frame_id.size()) + 4+8 );
  85. memcpy(p,point_cloud->points.data(),point_cloud->width * sizeof(pcl::PointXYZI));
  86. // std::cout<<"width = "<<point_cloud->width<<std::endl;
  87. iv::modulecomm::ModuleSendMsg(pasm,strOut,4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->size() * sizeof(pcl::PointXYZI));
  88. delete strOut;
  89. }
  90. static float SENSOR_HEIGHT = 2.1;
  91. static float VEHICLE_HEIGHT = 2.6;
  92. //static float local_max_slope_ = 10;
  93. //static float general_max_slope_ = 3;
  94. //static float concentric_divider_distance_ = 1.5;
  95. //static float min_height_threshold_ = 0.05;
  96. //static float reclass_distance_threshold_ = 10.0;
  97. static float GRID_SIZE = 2.0;
  98. static float SMALLGRID_SIZE = 0.2;
  99. static float Height_Thesh_Ratio = 0.1;
  100. static float General_Thresh_Ratio = 0.1;
  101. static float VEC_LEN = 200.0;
  102. static float HOR_LEN = 200.0;
  103. static float VEC_MIN = -100.0;
  104. static float HOR_MIN = -100.0;
  105. static int g_seq = 0;
  106. static float skip_xmin = -0.9;
  107. static float skip_ymin = -2.3;
  108. static float skip_xmax = 0.9;
  109. static float skip_ymax = 2.3;
  110. static void GridGetObs(pcl::PointCloud<pcl::PointXYZI>::Ptr & point_cloud,std::shared_ptr<std::vector<iv::ObstacleBasic>> lidar_obs)
  111. {
  112. // std::cout<<"enter gird obs"<<std::endl;
  113. int nVecSize = VEC_LEN/GRID_SIZE;
  114. int nHorSize = HOR_LEN/GRID_SIZE;
  115. bool * floor_find = new bool[(nVecSize+2)*(nHorSize+2)];
  116. float * floor_h_raw = new float[(nVecSize+2)*(nHorSize+2)];
  117. float * floor_h = new float[nVecSize*nHorSize];
  118. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud_nofloor(
  119. new pcl::PointCloud<pcl::PointXYZI>());
  120. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud_floor(
  121. new pcl::PointCloud<pcl::PointXYZI>());
  122. QDateTime dt = QDateTime::currentDateTime();
  123. point_cloud_floor->header.frame_id = "velodyne";
  124. point_cloud_floor->height = 1;
  125. point_cloud_floor->header.stamp = dt.currentMSecsSinceEpoch();
  126. point_cloud_floor->width = 0;
  127. point_cloud_floor->header.seq =g_seq;
  128. point_cloud_nofloor->header.frame_id = "velodyne";
  129. point_cloud_nofloor->height = 1;
  130. point_cloud_nofloor->header.stamp = dt.currentMSecsSinceEpoch();
  131. point_cloud_nofloor->width = 0;
  132. point_cloud_nofloor->header.seq =g_seq;
  133. g_seq++;
  134. int i,j;
  135. for(i=0;i<(nVecSize+2);i++)
  136. {
  137. for(j=0;j<(nHorSize+2);j++)
  138. {
  139. floor_find[i*(nHorSize+2) +j] = false;
  140. }
  141. }
  142. for(i=0;i<nVecSize;i++)
  143. {
  144. for(j=0;j<nHorSize;j++)
  145. {
  146. floor_h[i*nHorSize+j] = -SENSOR_HEIGHT;
  147. }
  148. }
  149. for(i=0;i<point_cloud->size();i++)
  150. {
  151. float x = point_cloud->at(i).x;
  152. float y = point_cloud->at(i).y;
  153. float z = point_cloud->at(i).z;
  154. if((x>=skip_xmin)&&(y>=skip_ymin)&&(x<=skip_xmax)&&(y<=skip_ymax))
  155. {
  156. continue;
  157. }
  158. float dis = sqrt(x*x + y*y);
  159. // if((dis>0.9)&&(z>(-SENSOR_HEIGHT-dis*General_Thresh_Ratio))&&(z<(-SENSOR_HEIGHT+dis*General_Thresh_Ratio)))
  160. if((z>(-SENSOR_HEIGHT-dis*General_Thresh_Ratio))&&(z<(-SENSOR_HEIGHT+dis*General_Thresh_Ratio)))
  161. {
  162. int Rpos,Cpos;
  163. Rpos = (y-VEC_MIN)/GRID_SIZE;
  164. Cpos = (x-HOR_MIN)/GRID_SIZE;
  165. if((Rpos>=0)&&(Rpos<nVecSize)&&(Cpos>=0)&&(Cpos<nHorSize))
  166. {
  167. int xPos = Rpos*(nHorSize+2) + Cpos+1;
  168. if(floor_find[xPos] == true)
  169. {
  170. if(z<floor_h_raw[xPos])
  171. {
  172. floor_h_raw[xPos] = z;
  173. }
  174. }
  175. else
  176. {
  177. floor_find[xPos]= true;
  178. floor_h_raw[xPos] = z;
  179. }
  180. }
  181. }
  182. }
  183. for(i=1;i<(nVecSize+1);i++)
  184. {
  185. for(j=1;j<(nHorSize+1);j++)
  186. {
  187. int m,n;
  188. bool bHave = false;
  189. float min;
  190. for(m=-1;m<=1;m++)
  191. {
  192. for(n=-1;n<=1;n++)
  193. {
  194. int xpos = (i+m)*(nHorSize+2) + j+n;
  195. if(floor_find[xpos])
  196. {
  197. if(bHave)
  198. {
  199. if(min<floor_h_raw[xpos])min = floor_h_raw[xpos];
  200. }
  201. else
  202. {
  203. min = floor_h_raw[xpos];
  204. bHave = true;
  205. }
  206. }
  207. }
  208. }
  209. if(bHave)floor_h[(i-1)*nHorSize +j] = min;
  210. }
  211. }
  212. //#ifdef OUT_GROUND
  213. for(i=0;i<point_cloud->size();i++)
  214. {
  215. pcl::PointXYZI po = point_cloud->at(i);
  216. float x = point_cloud->at(i).x;
  217. float y = point_cloud->at(i).y;
  218. float z = point_cloud->at(i).z;
  219. if((x>=skip_xmin)&&(y>=skip_ymin)&&(x<=skip_xmax)&&(y<=skip_ymax))
  220. {
  221. continue;
  222. }
  223. // float dis = sqrt(x*x + y*y);
  224. int Rpos,Cpos;
  225. Rpos = (y-VEC_MIN)/GRID_SIZE;
  226. Cpos = (x-HOR_MIN)/GRID_SIZE;
  227. if((Rpos>=0)&&(Rpos<nVecSize)&&(Cpos>=0)&&(Cpos<nHorSize))
  228. {
  229. if((z-floor_h[Rpos*nHorSize+Cpos])>0.3)
  230. {
  231. point_cloud_nofloor->push_back(po);
  232. ++point_cloud_nofloor->width;
  233. }
  234. else
  235. {
  236. point_cloud_floor->push_back(po);
  237. ++point_cloud_floor->width;
  238. }
  239. }
  240. }
  241. //#endif
  242. // for(i=0;i<nVecSize;i++)
  243. // {
  244. // char strOut[3000];
  245. // char strTem[30];
  246. // snprintf(strOut,3000,"i = %d",i);
  247. // for(j=0;j<nHorSize;j++)
  248. // {
  249. // // floor_h[i*nHorSize+j] = -SENSOR_HEIGHT;
  250. // snprintf(strTem,30,"%6.3f ",floor_h[i*nHorSize+j]);
  251. // strncat(strOut,strTem,3000);
  252. // }
  253. // qDebug(strOut);
  254. // }
  255. #ifdef OUT_GROUND
  256. writepctosm(point_cloud_floor,g_lidar_pc_floor);
  257. writepctosm(point_cloud_nofloor,g_lidar_pc_nofloor);
  258. #endif
  259. int NYC = VEC_LEN/SMALLGRID_SIZE;
  260. int NXC = HOR_LEN/SMALLGRID_SIZE;
  261. iv::LidarGrid * pobsgrid = new iv::LidarGrid[NYC*NXC];//from 50m back 50m left 25m right 25m
  262. // int i,j;
  263. for(i=0;i<NYC;i++)
  264. {
  265. for(j=0;j<NXC;j++)
  266. {
  267. iv::LidarGrid * p = pobsgrid + i*NXC+j;
  268. p->pointcount = 0;
  269. int Rpos,Cpos;
  270. Rpos = (i*SMALLGRID_SIZE)/GRID_SIZE;
  271. Cpos = (j*SMALLGRID_SIZE)/GRID_SIZE;
  272. if((Rpos>=0)&&(Rpos<nVecSize)&&(Cpos>=0)&&(Cpos<nHorSize))
  273. {
  274. int xPos = Rpos*nHorSize + Cpos;
  275. p->groundheight = floor_h[xPos];
  276. }
  277. else
  278. {
  279. p->groundheight = -SENSOR_HEIGHT+1000;
  280. }
  281. p->low = -SENSOR_HEIGHT+1000;
  282. p->high = -SENSOR_HEIGHT - 1000;
  283. p->obshight = 0;
  284. p->ob = 0;
  285. }
  286. }
  287. for(i=0;i<point_cloud_nofloor->size();i++)
  288. {
  289. pcl::PointXYZI pxyzi = point_cloud_nofloor->at(i);
  290. int x,y;
  291. x = (int)((pxyzi.y-VEC_MIN)/SMALLGRID_SIZE);
  292. y = (int)((pxyzi.x-HOR_MIN)/SMALLGRID_SIZE);
  293. if((x>=0)&&(x<NXC)&&(y<NYC)&&(y>=0))
  294. {
  295. iv::LidarGrid * p = pobsgrid + x*NXC+y;
  296. p->ob++;
  297. if(pxyzi.z<p->low)p->low = pxyzi.z;
  298. if(pxyzi.z>p->high)p->high = pxyzi.z;
  299. }
  300. }
  301. for(i=0;i<NYC;i++)
  302. {
  303. for(j=0;j<NXC;j++)
  304. {
  305. iv::LidarGrid * p = pobsgrid + i*NXC+j;
  306. if(p->ob>=3)
  307. {
  308. if(p->low>(p->groundheight+VEHICLE_HEIGHT))
  309. {
  310. // std::cout<<"low high"<<std::endl;
  311. }
  312. else
  313. {
  314. // temp.nomal_x = (j-125)*0.2+0.1;
  315. // temp.nomal_y = (i-250)*0.2+0.1;
  316. iv::ObstacleBasic temp;
  317. temp.low = p->low;
  318. temp.high = p->high;
  319. temp.nomal_z = p->high-p->low;
  320. temp.nomal_x = j*SMALLGRID_SIZE + 0.1+HOR_MIN;
  321. temp.nomal_y = i*SMALLGRID_SIZE +0.1 +VEC_MIN;
  322. lidar_obs->push_back(temp);
  323. }
  324. }
  325. }
  326. }
  327. delete pobsgrid;
  328. delete floor_find;
  329. delete floor_h_raw;
  330. delete floor_h;
  331. }
  332. #include <QTime>
  333. static void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  334. {
  335. // std::cout<<"enter listen."<<std::endl;
  336. if(nSize <=16)return;
  337. int xin = index;
  338. xin++;
  339. unsigned int * pHeadSize = (unsigned int *)strdata;
  340. if(*pHeadSize > nSize)
  341. {
  342. std::cout<<"ListenPointCloud data is small headsize ="<<*pHeadSize<<" data size is"<<nSize<<std::endl;
  343. }
  344. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  345. new pcl::PointCloud<pcl::PointXYZI>());
  346. int nNameSize;
  347. nNameSize = *pHeadSize - 4-4-8;
  348. char * strName = new char[nNameSize+1];strName[nNameSize] = 0;
  349. memcpy(strName,(char *)((char*)strdata +4),nNameSize);
  350. point_cloud->header.frame_id = strName;
  351. memcpy(&point_cloud->header.seq,((char*)strdata)+4+nNameSize,4);
  352. memcpy(&point_cloud->header.stamp,(char *)strdata+4+nNameSize+4,8);
  353. int nPCount = (nSize - *pHeadSize)/sizeof(pcl::PointXYZI);
  354. int i;
  355. pcl::PointXYZI * p;
  356. p = (pcl::PointXYZI *)((char*)strdata + *pHeadSize);
  357. for(i=0;i<nPCount;i++)
  358. {
  359. pcl::PointXYZI xp;
  360. xp.x = p->x;
  361. xp.y = p->y;
  362. xp.z = p->z;
  363. xp.intensity = p->intensity;
  364. point_cloud->push_back(xp);
  365. p++;
  366. }
  367. std::shared_ptr<std::vector<iv::ObstacleBasic>> lidar_obs(new std::vector<iv::ObstacleBasic>);
  368. GridGetObs(point_cloud,lidar_obs);
  369. // perception_lidar_vv7_ProcObs(point_cloud,lidar_obs);
  370. // std::cout<<"prc."<<std::endl;
  371. if(g_robosys == 0)
  372. {
  373. if(lidar_obs->size() == 0)
  374. {
  375. iv::ObstacleBasic temp;
  376. temp.low = 0;
  377. temp.high = 3.0;
  378. temp.nomal_z = 3.0;
  379. temp.nomal_x = 1000;
  380. temp.nomal_y = 1000;
  381. lidar_obs->push_back(temp);
  382. }
  383. if(lidar_obs->size() >0)iv::modulecomm::ModuleSendMsg(glidar_obs,(char *)(lidar_obs->data()),lidar_obs->size()*sizeof(iv::ObstacleBasic));
  384. }
  385. else
  386. {
  387. g_robosys--;
  388. if(g_robosys<0)
  389. {
  390. g_robosys = 0;
  391. }
  392. }
  393. gfault->SetFaultState(0, 0, "ok");
  394. // return;
  395. // gw->UpdatePointCloud(point_cloud);
  396. }
  397. void PERCEPTION_LIDAR_VV7SHARED_EXPORT StartPerception_lidar_vv7()
  398. {
  399. std::cout<<"HHINow Start LIDAR Perception"<<std::endl;
  400. glidar_obs = iv::modulecomm::RegisterSend(gstr_outputmemname,20000000,3);
  401. #ifdef OUT_GROUND
  402. g_lidar_pc_floor = iv::modulecomm::RegisterSend("lidar_pc_floor",20000000,3);
  403. g_lidar_pc_nofloor = iv::modulecomm::RegisterSend("lidar_pc_nofloor",20000000,3);
  404. #endif
  405. glidar_pc = iv::modulecomm::RegisterRecv(gstr_inputmemname,ListenPointCloud);
  406. }
  407. void PERCEPTION_LIDAR_VV7SHARED_EXPORT StopPerception_lidar_vv7()
  408. {
  409. }
  410. void decodeyaml(const char * stryaml)
  411. {
  412. YAML::Node config;
  413. try
  414. {
  415. config = YAML::LoadFile(stryaml);
  416. }
  417. catch(YAML::BadFile e)
  418. {
  419. givlog->verbose("load yaml error.");
  420. return;
  421. }
  422. if(config["SensorHeight"])
  423. {
  424. strncpy(gstr_sensorheight,config["SensorHeight"].as<std::string>().data(),255);
  425. }
  426. if(config["VehicleHeight"])
  427. {
  428. strncpy(gstr_vehicleheight,config["VehicleHeight"].as<std::string>().data(),255);
  429. }
  430. if(config["inputmemname"])
  431. {
  432. strncpy(gstr_inputmemname,config["inputmemname"].as<std::string>().data(),255);
  433. }
  434. if(config["outputmemname"])
  435. {
  436. strncpy(gstr_outputmemname,config["outputmemname"].as<std::string>().data(),255);
  437. }
  438. if(config["skip_xmin"])
  439. {
  440. strncpy(gstr_skipxmin,config["skip_xmin"].as<std::string>().data(),255);
  441. }
  442. if(config["skip_xmax"])
  443. {
  444. strncpy(gstr_skipxmax,config["skip_xmax"].as<std::string>().data(),255);
  445. }
  446. if(config["skip_ymin"])
  447. {
  448. strncpy(gstr_skipymin,config["skip_ymin"].as<std::string>().data(),255);
  449. }
  450. if(config["skip_ymax"])
  451. {
  452. strncpy(gstr_skipymax,config["skip_ymax"].as<std::string>().data(),255);
  453. }
  454. // std::cout<<gstr_memname<<std::endl;
  455. // std::cout<<gstr_rollang<<std::endl;
  456. // std::cout<<gstr_inclinationang_xaxis<<std::endl;
  457. // std::cout<<gstr_inclinationang_yaxis<<std::endl;
  458. // std::cout<<gstr_hostip<<std::endl;
  459. // std::cout<<gstr_port<<std::endl;
  460. }
  461. char gstr_yaml[256];
  462. void print_useage()
  463. {
  464. std::cout<<" -s --setyaml $yaml : port . eq. -s rs1.yaml"<<std::endl;
  465. std::cout<<" -h --help print help"<<std::endl;
  466. }
  467. int GetOptLong(int argc, char *argv[]) {
  468. int nRtn = 0;
  469. int opt; // getopt_long() 的返回值
  470. int digit_optind = 0; // 设置短参数类型及是否需要参数
  471. // 如果option_index非空,它指向的变量将记录当前找到参数符合long_opts里的
  472. // 第几个元素的描述,即是long_opts的下标值
  473. int option_index = 0;
  474. // 设置短参数类型及是否需要参数
  475. const char *optstring = "s:h";
  476. // 设置长参数类型及其简写,比如 --reqarg <==>-r
  477. /*
  478. struct option {
  479. const char * name; // 参数的名称
  480. int has_arg; // 是否带参数值,有三种:no_argument, required_argument,optional_argument
  481. int * flag; // 为空时,函数直接将 val 的数值从getopt_long的返回值返回出去,
  482. // 当非空时,val的值会被赋到 flag 指向的整型数中,而函数返回值为0
  483. int val; // 用于指定函数找到该选项时的返回值,或者当flag非空时指定flag指向的数据的值
  484. };
  485. 其中:
  486. no_argument(即0),表明这个长参数不带参数(即不带数值,如:--name)
  487. required_argument(即1),表明这个长参数必须带参数(即必须带数值,如:--name Bob)
  488. optional_argument(即2),表明这个长参数后面带的参数是可选的,(即--name和--name Bob均可)
  489. */
  490. static struct option long_options[] = {
  491. {"setyaml", required_argument, NULL, 's'},
  492. {"help", no_argument, NULL, 'h'},
  493. // {"optarg", optional_argument, NULL, 'o'},
  494. {0, 0, 0, 0} // 添加 {0, 0, 0, 0} 是为了防止输入空值
  495. };
  496. while ( (opt = getopt_long(argc,
  497. argv,
  498. optstring,
  499. long_options,
  500. &option_index)) != -1) {
  501. // printf("opt = %c\n", opt); // 命令参数,亦即 -a -b -n -r
  502. // printf("optarg = %s\n", optarg); // 参数内容
  503. // printf("optind = %d\n", optind); // 下一个被处理的下标值
  504. // printf("argv[optind - 1] = %s\n", argv[optind - 1]); // 参数内容
  505. // printf("option_index = %d\n", option_index); // 当前打印参数的下标值
  506. // printf("\n");
  507. switch(opt)
  508. {
  509. case 's':
  510. strncpy(gstr_yaml,optarg,255);
  511. break;
  512. case 'h':
  513. print_useage();
  514. nRtn = 1; //because use -h
  515. break;
  516. default:
  517. break;
  518. }
  519. }
  520. return nRtn;
  521. }
  522. int main(int argc, char *argv[])
  523. {
  524. RegisterIVBackTrace();
  525. showversion("detection_lidar_grid");
  526. QCoreApplication a(argc, argv);
  527. gfault = new iv::Ivfault("lidar_grid");
  528. givlog = new iv::Ivlog("lidar_grid");
  529. snprintf(gstr_yaml,255,"");
  530. int nRtn = GetOptLong(argc,argv);
  531. if(nRtn == 1) //show help,so exit.
  532. {
  533. return 0;
  534. }
  535. snprintf(gstr_sensorheight,255,"2.0");
  536. snprintf(gstr_vehicleheight,255,"2.3");
  537. snprintf(gstr_inputmemname,255,"lidar_pc");
  538. snprintf(gstr_outputmemname,255,"lidar_obs");
  539. snprintf(gstr_skipxmin,255,"-0.9");
  540. snprintf(gstr_skipxmax,255,"0.9");
  541. snprintf(gstr_skipymin,255,"-2.3");
  542. snprintf(gstr_skipymax,255,"2.3");
  543. givlog->verbose("yaml is %s ",gstr_yaml);
  544. if(strnlen(gstr_yaml,255)>0)
  545. {
  546. decodeyaml(gstr_yaml);
  547. }
  548. SENSOR_HEIGHT = atof(gstr_sensorheight);
  549. VEHICLE_HEIGHT = atof(gstr_vehicleheight);
  550. skip_xmin = atof(gstr_skipxmin);
  551. skip_xmax = atof(gstr_skipxmax);
  552. skip_ymin = atof(gstr_skipymin);
  553. skip_ymax = atof(gstr_skipymax);
  554. StartPerception_lidar_vv7();
  555. return a.exec();
  556. }