main.cpp 45 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547
  1. #include <QCoreApplication>
  2. #include <math.h>
  3. #include <string>
  4. #include <thread>
  5. #include <QFile>
  6. #include "OpenDrive/OpenDrive.h"
  7. #include "OpenDrive/OpenDriveXmlParser.h"
  8. #include "globalplan.h"
  9. #include "gpsimu.pb.h"
  10. #include "mapdata.pb.h"
  11. #include "mapglobal.pb.h"
  12. #include "v2x.pb.h"
  13. #include "modulecomm.h"
  14. #include "xmlparam.h"
  15. #include "gps_type.h"
  16. #include "xodrdijkstra.h"
  17. #include "gnss_coordinate_convert.h"
  18. #include "ivexit.h"
  19. #include "ivversion.h"
  20. #include "ivbacktrace.h"
  21. #include <signal.h>
  22. #include "service_roi_xodr.h"
  23. #include "ivservice.h"
  24. #ifdef USE_TMERS
  25. #include "proj.h"
  26. //#include "projects.h"
  27. PJ_CONTEXT *C;//用于处理多线程程序
  28. PJ *P;//初始化投影目标
  29. PJ *norm;//初始化投影目标
  30. #endif
  31. OpenDrive mxodr;
  32. xodrdijkstra * gpxd;
  33. bool gmapload = false;
  34. double glat0,glon0,ghead0;
  35. double gvehiclewidth = 2.0;
  36. bool gbExtendMap = true;
  37. static bool gbSideEnable = false;
  38. static bool gbSideLaneEnable = false;
  39. static std::string gstrcdata;
  40. static void * gpa;
  41. static void * gpasrc;
  42. static void * gpmap;
  43. static void * gpagps;
  44. static void * gpasimple;
  45. static void * gpav2x;
  46. static void * gpanewtrace;
  47. static void * gpamapglobal;
  48. iv::Ivfault *gfault = nullptr;
  49. iv::Ivlog *givlog = nullptr;
  50. static QCoreApplication * gApp;
  51. service_roi_xodr gsrx;
  52. namespace iv {
  53. struct simpletrace
  54. {
  55. double gps_lat = 0;//纬度
  56. double gps_lng = 0;//经度
  57. double gps_x = 0;
  58. double gps_y = 0;
  59. double gps_z = 0;
  60. double ins_heading_angle = 0; //航向角
  61. };
  62. }
  63. /**
  64. *
  65. *
  66. *
  67. *
  68. * */
  69. bool LoadXODR(std::string strpath)
  70. {
  71. OpenDriveXmlParser xp(&mxodr);
  72. xp.ReadFile(strpath);
  73. std::cout<<"road cout is "<<mxodr.GetRoadCount()<<std::endl;
  74. if(mxodr.GetRoadCount() < 1)
  75. {
  76. gmapload = true;
  77. return false;
  78. }
  79. xodrdijkstra * pxd = new xodrdijkstra(&mxodr);
  80. gpxd = pxd;
  81. // std::vector<int> xpath = pxd->getpath(10001,2,30012,2);
  82. // pxd->getgpspoint(10001,2,30012,2,xpath);
  83. int i;
  84. double nlenth = 0;
  85. int nroadsize = mxodr.GetRoadCount();
  86. for(i=0;i<nroadsize;i++)
  87. {
  88. Road * px = mxodr.GetRoad(i);
  89. nlenth = nlenth + px->GetRoadLength();
  90. int bloksize = px->GetGeometryBlockCount();
  91. if(px->GetGeometryBlock(0)->GetGeometryAt(0)->GetGeomType() == 4)
  92. {
  93. GeometryParamPoly3 * p = (GeometryParamPoly3 *) px->GetGeometryBlock(0)->GetGeometryAt(0);
  94. double a = p->GetuA();
  95. a = p->GetuB();
  96. a = p->GetuC();
  97. a = p->GetuD();
  98. a = p->GetvA();
  99. }
  100. }
  101. // void Header::GetAllParams(unsigned short int &revMajor, unsigned short int &revMinor, string &name, float &version, string &date,
  102. // double &north, double &south, double &east,double &west,double &lat0,double &lon0, double & hdg0)
  103. unsigned short int revMajor,revMinor;
  104. std::string name,date;
  105. float version;
  106. double north,south,east,west,lat0,lon0,hdg0;
  107. if(mxodr.GetHeader() != 0)
  108. {
  109. mxodr.GetHeader()->GetAllParams(revMajor,revMinor,name,version,date,north,south,east,west,lat0,lon0,hdg0);
  110. glat0 = lat0;
  111. glon0 = lon0;
  112. }
  113. Road * proad1 = mxodr.GetRoad(0);
  114. givlog->info("road name is %s",proad1->GetRoadName().data());
  115. std::cout<<" road name is "<<proad1->GetRoadName()<<std::endl;
  116. gsrx.SetXODR(&mxodr);
  117. }
  118. class roadx
  119. {
  120. public:
  121. roadx * para;
  122. std::vector<roadx> child;
  123. int nlen;
  124. };
  125. #define EARTH_RADIUS 6370856.0
  126. //从1到2的距离和方向
  127. int CalcDisAngle(double lat1,double lon1,double lat2,double lon2,double * pLatDis,double * pLonDis,double * pDis,double * pangle)
  128. {
  129. double a,b;
  130. double LonDis,LatDis;
  131. double LonRadius;
  132. double Dis;
  133. double angle;
  134. if((lat1 == lat2)&&(lon1 == lon2))return -1;
  135. LonRadius = EARTH_RADIUS * cos(lat2/(180.0/M_PI));
  136. a = (EARTH_RADIUS * M_PI*2.0/360.0)/(100000.0);
  137. b = lat2 - lat1; b = b*100000.0;
  138. LatDis = a*b;
  139. a = (LonRadius * M_PI*2.0/360.0)/100000.0;
  140. b = lon2 - lon1; b = b*100000.0;
  141. LonDis = a*b;
  142. Dis = sqrt(LatDis*LatDis + LonDis *LonDis);
  143. angle = acos(fabs(LonDis)/Dis);
  144. angle = angle * 180.0/M_PI;
  145. if(LonDis > 0)
  146. {
  147. if(LatDis > 0)angle = 90.0 - angle;
  148. else angle= 90.0+angle;
  149. }
  150. else
  151. {
  152. if(LatDis > 0)angle = 270.0+angle;
  153. else angle = 270.0-angle;
  154. }
  155. if(pLatDis != 0)*pLatDis = LatDis;
  156. if(pLonDis != 0)*pLonDis = LonDis;
  157. if(pDis != 0)*pDis = Dis;
  158. if(pangle != 0)*pangle = angle;
  159. }
  160. //==========================================================
  161. //高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
  162. //void GaussProjCal(double longitude, double latitude, double *X, double *Y)
  163. //{
  164. // int ProjNo = 0; int ZoneWide; ////带宽
  165. // double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
  166. // double a, f, e2, ee, NN, T, C, A, M, iPI;
  167. // iPI = 0.0174532925199433; ////3.1415926535898/180.0;
  168. // ZoneWide = 6; ////6度带宽
  169. // a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
  170. // ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
  171. // ProjNo = (int)(longitude / ZoneWide);
  172. // longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
  173. // longitude0 = longitude0 * iPI;
  174. // latitude0 = 0;
  175. // longitude1 = longitude * iPI; //经度转换为弧度
  176. // latitude1 = latitude * iPI; //纬度转换为弧度
  177. // e2 = 2 * f - f * f;
  178. // ee = e2 * (1.0 - e2);
  179. // NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
  180. // T = tan(latitude1)*tan(latitude1);
  181. // C = ee * cos(latitude1)*cos(latitude1);
  182. // A = (longitude1 - longitude0)*cos(latitude1);
  183. // M = a * ((1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256)*latitude1 - (3 * e2 / 8 + 3 * e2*e2 / 32 + 45 * e2*e2
  184. // *e2 / 1024)*sin(2 * latitude1)
  185. // + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
  186. // xval = NN * (A + (1 - T + C)*A*A*A / 6 + (5 - 18 * T + T * T + 72 * C - 58 * ee)*A*A*A*A*A / 120);
  187. // yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
  188. // + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
  189. // X0 = 1000000L * (ProjNo + 1) + 500000L;
  190. // Y0 = 0;
  191. // xval = xval + X0; yval = yval + Y0;
  192. // *X = xval;
  193. // *Y = yval;
  194. //}
  195. #include <math.h>
  196. static void OffLngLat(double fLat0,double fLng0,double & fLat,double & fLng,double fHeading,double x,double y)
  197. {
  198. double fxdiff,fydiff;
  199. double xoff = y*(-1);
  200. double yoff = x;
  201. fxdiff = 0+xoff * cos(fHeading*M_PI/180.0)+ yoff*sin(fHeading*M_PI/180.0); //East
  202. fydiff = 0-xoff * sin(fHeading*M_PI/180.0)+ yoff*cos(fHeading*M_PI/180.0); //South
  203. double fEarthRadius = 6378245.0;
  204. double ns1d = fEarthRadius*2*M_PI/360.0;
  205. double fewRadius = fEarthRadius * cos(fLat0*M_PI/180.0);
  206. double ew1d = fewRadius * 2*M_PI/360.0;
  207. fLat = fLat0 + fydiff/ns1d;
  208. fLng = fLng0 + fxdiff/ew1d;
  209. }
  210. void CalcXY(const double lat0,const double lon0,const double hdg0,
  211. const double lat,const double lon,
  212. double & x,double & y)
  213. {
  214. double x0,y0;
  215. GaussProjCal(lon0,lat0,&x0,&y0);
  216. GaussProjCal(lon,lat,&x,&y);
  217. x = x - x0;
  218. y = y- y0;
  219. // double ang,dis;
  220. // CalcDisAngle(lat0,lon0,lat,lon,0,0,&dis,&ang);
  221. // double xang = hdg0 - ang;
  222. // while(xang<0)xang = xang + 360.0;
  223. // x = dis * cos(xang * M_PI/180.0);
  224. // y = dis * sin(xang * M_PI/180.0);
  225. }
  226. //void CalcLatLon(const double lat0,const double lon0,const double hdg0,
  227. // const double x,const double y,const double xyhdg,
  228. // double &lat,double & lon, double & hdg)
  229. //{
  230. // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
  231. // hdg = hdg0 - xyhdg * 180.0/M_PI;
  232. // while(hdg < 0)hdg = hdg + 360;
  233. // while(hdg >= 360)hdg = hdg - 360;
  234. //}
  235. void CalcLatLon(const double lat0,const double lon0,
  236. const double x,const double y,
  237. double &lat,double & lon)
  238. {
  239. double x0,y0;
  240. GaussProjCal(lon0,lat0,&x0,&y0);
  241. double x_gps,y_gps;
  242. x_gps = x0+x;
  243. y_gps = y0+y;
  244. GaussProjInvCal(x_gps,y_gps,&lon,&lat);
  245. }
  246. void CalcLatLon(const double lat0,const double lon0,const double hdg0,
  247. const double x,const double y,const double xyhdg,
  248. double &lat,double & lon, double & hdg)
  249. {
  250. double x0,y0;
  251. GaussProjCal(lon0,lat0,&x0,&y0);
  252. double x_gps,y_gps;
  253. x_gps = x0+x;
  254. y_gps = y0+y;
  255. GaussProjInvCal(x_gps,y_gps,&lon,&lat);
  256. // hdg = hdg0 -xyhdg * 270/M_PI;
  257. hdg = 90 - xyhdg* 180.0/M_PI;
  258. // OffLngLat(lat0,lon0,lat,lon,hdg0,x,y);
  259. // hdg = hdg0 - xyhdg * 180.0/M_PI;
  260. while(hdg < 0)hdg = hdg + 360;
  261. while(hdg >= 360)hdg = hdg - 360;
  262. #ifdef USE_TMERS
  263. if(gstrcdata.length()>3)
  264. {
  265. PJ_COORD cp;//初始化投影坐标
  266. cp.enu.e = x;
  267. cp.enu.n = y;
  268. cp = proj_trans(P, PJ_INV, cp);//xy坐标转化为经纬度坐标
  269. lon = cp.lp.lam;
  270. lat = cp.lp.phi;
  271. }
  272. #endif
  273. }
  274. class xodrobj
  275. {
  276. public:
  277. double flatsrc;
  278. double flonsrc;
  279. double fhgdsrc;
  280. double flat;
  281. double flon;
  282. int lane;
  283. };
  284. static xodrobj gsrc;
  285. void ShareMapGlobal(std::vector<PlanPoint> & xvectorPlan)
  286. {
  287. iv::map::mapglobal xglobal;
  288. unsigned int i;
  289. unsigned int nsize = static_cast<unsigned int >(xvectorPlan.size());
  290. for(i=0;i<nsize;i++)
  291. {
  292. iv::map::pointglobal * ppoint = xglobal.add_point();
  293. double gps_lon,gps_lat,gps_heading;
  294. CalcLatLon(glat0,glon0,ghead0,xvectorPlan[i].x,xvectorPlan[i].y,xvectorPlan[i].hdg,gps_lat,
  295. gps_lon,gps_heading);
  296. ppoint->set_gps_lat(gps_lat);
  297. ppoint->set_gps_lng(gps_lon);
  298. ppoint->set_ins_heading_angle(gps_heading);
  299. double gps_x,gps_y;
  300. GaussProjCal(gps_lon,gps_lat,&gps_x,&gps_y);
  301. ppoint->set_gps_x(gps_x);
  302. ppoint->set_gps_y(gps_y);
  303. ppoint->set_gps_z(0);
  304. ppoint->set_mfcurvature(xvectorPlan[i].mfCurvature);
  305. ppoint->set_mfdistolaneleft(xvectorPlan[i].mfDisToLaneLeft);
  306. ppoint->set_mfdistoroadleft(xvectorPlan[i].mfDisToRoadLeft);
  307. ppoint->set_mflanewidth(xvectorPlan[i].mWidth);
  308. ppoint->set_mfroadwidth(xvectorPlan[i].mfRoadWidth);
  309. ppoint->set_speed(xvectorPlan[i].speed);
  310. unsigned int nlanecount = static_cast<unsigned int>(xvectorPlan[i].mVectorLaneWidth.size());
  311. unsigned int j;
  312. for(j=0;j<nlanecount;j++)
  313. {
  314. ppoint->add_mfvectorlanewidth(xvectorPlan[i].mVectorLaneWidth[j]);
  315. }
  316. ppoint->set_mlanecount(xvectorPlan[i].mLaneCount);
  317. ppoint->set_mlanecur(xvectorPlan[i].mLaneCur);
  318. }
  319. int bytesize = static_cast<int>(xglobal.ByteSize()) ;
  320. std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[bytesize]);
  321. if(xglobal.SerializePartialToArray(pstr_ptr.get(),bytesize))
  322. {
  323. iv::modulecomm::ModuleSendMsg(gpamapglobal,pstr_ptr.get(),static_cast<unsigned int>(bytesize) );
  324. }
  325. else
  326. {
  327. std::cout<<" ShareMapGlobal Serialzie Fail."<<std::endl;
  328. }
  329. }
  330. void ShareMap(std::vector<iv::GPSData> navigation_data)
  331. {
  332. if(navigation_data.size()<1)return;
  333. iv::GPS_INS x;
  334. x = *(navigation_data.at(0));
  335. char * data = new char[sizeof(iv::GPS_INS)*navigation_data.size()];
  336. int gpssize = sizeof(iv::GPS_INS);
  337. int i;
  338. for(i=0;i<navigation_data.size();i++)
  339. {
  340. x = *(navigation_data.at(i));
  341. memcpy(data+i*gpssize,&x,gpssize);
  342. }
  343. iv::modulecomm::ModuleSendMsg(gpmap,data,navigation_data.size()*gpssize);
  344. int nsize = 100;
  345. int nstep = 1;
  346. if(navigation_data.size() < 100)
  347. {
  348. nsize = navigation_data.size();
  349. }
  350. else
  351. {
  352. nstep = navigation_data.size()/100;
  353. }
  354. iv::simpletrace psim[100];
  355. for(i=0;i<nsize;i++)
  356. {
  357. x = *(navigation_data.at(i*nstep));
  358. psim[i].gps_lat = x.gps_lat;
  359. psim[i].gps_lng = x.gps_lng;
  360. psim[i].gps_z = x.gps_z;
  361. psim[i].gps_x = x.gps_x;
  362. psim[i].gps_y = x.gps_y;
  363. psim[i].ins_heading_angle = x.ins_heading_angle;
  364. }
  365. if(navigation_data.size()>100)
  366. {
  367. int nlast = 99;
  368. x = *(navigation_data.at(navigation_data.size()-1));
  369. psim[nlast].gps_lat = x.gps_lat;
  370. psim[nlast].gps_lng = x.gps_lng;
  371. psim[nlast].gps_z = x.gps_z;
  372. psim[nlast].gps_x = x.gps_x;
  373. psim[nlast].gps_y = x.gps_y;
  374. psim[nlast].ins_heading_angle = x.ins_heading_angle;
  375. }
  376. iv::modulecomm::ModuleSendMsg(gpasimple,(char *)psim,nsize * sizeof(iv::simpletrace));
  377. delete data;
  378. }
  379. static void ToGPSTrace(std::vector<PlanPoint> xPlan)
  380. {
  381. // double x_src,y_src,x_dst,y_dst;
  382. // x_src = -26;y_src = 10;
  383. // x_dst = -50;y_dst = -220;
  384. int i;
  385. int nSize = xPlan.size();
  386. std::vector<iv::GPSData> mapdata;
  387. QFile xfile;
  388. QString strpath;
  389. strpath = getenv("HOME");
  390. strpath = strpath + "/map/maptrace.txt";
  391. xfile.setFileName(strpath);
  392. bool bFileOpen = xfile.open(QIODevice::ReadWrite);
  393. for(i=0;i<nSize;i++)
  394. {
  395. iv::GPSData data(new iv::GPS_INS);
  396. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  397. data->gps_lng,data->ins_heading_angle);
  398. data->index = i;
  399. data->speed = xPlan[i].speed;
  400. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  401. givlog->debug(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  402. data->gps_lng,data->ins_heading_angle);
  403. data->roadSum = xPlan[i].mnLaneTotal;
  404. data->roadMode = 0;
  405. data->roadOri = xPlan[i].mnLaneori;
  406. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  407. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  408. data->mfLaneWidth = xPlan[i].mWidth;
  409. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  410. data->mnLaneChangeMark = xPlan[i].lanmp;
  411. if(xPlan[i].lanmp == -1)data->roadMode = 15;
  412. if(xPlan[i].lanmp == 1)data->roadMode = 14;
  413. mapdata.push_back(data);
  414. char strline[255];
  415. snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\n",
  416. i,data->gps_lng,data->gps_lat,0,0,data->ins_heading_angle,0,0,0,0);
  417. if(bFileOpen) xfile.write(strline);
  418. // fout << gps_index << "\t" << data->gps_lng << "\t" << data->gps_lat << "\t" << ServiceCarStatus.location->speed_mode << "\t" << ServiceCarStatus.location->mode2 << "\t" << data->ins_heading_angle << "\t" << obs_modes << "\t" << speed_modes << "\t" << lane_num << "\t" << lane_status <<"\t" <<road_width <<std::endl;
  419. }
  420. if(bFileOpen)xfile.close();
  421. ShareMap(mapdata);
  422. }
  423. int avoidroadid[] = {10002,10019,10003,10098,10099,10063,10099,10100,10104,10110,10111};
  424. inline bool isboringroad(int nroadid)
  425. {
  426. int i;
  427. bool brtn = false;
  428. for(i=0;i<11;i++)
  429. {
  430. if(avoidroadid[i] == nroadid)
  431. {
  432. brtn = true;
  433. break;
  434. }
  435. }
  436. return brtn;
  437. }
  438. void CalcLaneSide(std::vector<PlanPoint> & xPlan)
  439. {
  440. const double fsidedis = 0.3;
  441. const int nChangePoint = 150;
  442. const int nStopPoint = 50;
  443. if(xPlan.size()<nChangePoint)return;
  444. int i;
  445. int nsize = xPlan.size();
  446. for(i=(nsize-1);i>=(nsize - nStopPoint);i--)
  447. {
  448. double fMove = xPlan[i].mfRoadWidth - xPlan[i].mfDisToRoadLeft - (gvehiclewidth/2.0 + fsidedis);
  449. // double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  450. double xold = xPlan[i].x;
  451. double yold = xPlan[i].y;
  452. xPlan[i].x = xold + fMove*cos(xPlan[i].hdg - M_PI/2.0);
  453. xPlan[i].y = yold + fMove*sin(xPlan[i].hdg - M_PI/2.0);
  454. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fMove;
  455. }
  456. for(i=(nsize-nStopPoint-1);i>=(nsize - nChangePoint);i--)
  457. {
  458. double fMove = xPlan[i].mfRoadWidth - xPlan[i].mfDisToRoadLeft - (gvehiclewidth/2.0 + fsidedis);
  459. // double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  460. double xold = xPlan[i].x;
  461. double yold = xPlan[i].y;
  462. double fRatio = 1.0 - ((nsize-nStopPoint) -i )*1.0/(nChangePoint-nStopPoint);
  463. xPlan[i].x = xold + fRatio*fMove*cos(xPlan[i].hdg - M_PI/2.0);
  464. xPlan[i].y = yold + fRatio*fMove*sin(xPlan[i].hdg - M_PI/2.0);
  465. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fRatio*fMove;
  466. }
  467. return;
  468. }
  469. void CalcSide(std::vector<PlanPoint> & xPlan)
  470. {
  471. const double fsidedis = 0.3;
  472. const int nChangePoint = 150;
  473. const int nStopPoint = 50;
  474. if(xPlan.size()<nChangePoint)return;
  475. bool bChange = true;
  476. int i;
  477. int nsize = xPlan.size();
  478. for(i=(nsize-1);i>=(nsize - nChangePoint);i--)
  479. {
  480. if(xPlan[i].mWidth<(2.0*(gvehiclewidth/2.0+fsidedis)))
  481. {
  482. std::cout<<" Because Lane is narrow, not change."<<std::endl;
  483. bChange = false;
  484. break;
  485. }
  486. }
  487. if(bChange == false)return;
  488. for(i=(nsize-1);i>=(nsize - nStopPoint);i--)
  489. {
  490. double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  491. double xold = xPlan[i].x;
  492. double yold = xPlan[i].y;
  493. xPlan[i].x = xold + fMove*cos(xPlan[i].hdg - M_PI/2.0);
  494. xPlan[i].y = yold + fMove*sin(xPlan[i].hdg - M_PI/2.0);
  495. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fMove;
  496. }
  497. for(i=(nsize-nStopPoint-1);i>=(nsize - nChangePoint);i--)
  498. {
  499. double fMove = xPlan[i].mWidth/2.0 - (gvehiclewidth/2.0 + fsidedis);
  500. double xold = xPlan[i].x;
  501. double yold = xPlan[i].y;
  502. double fRatio = 1.0 - ((nsize-nStopPoint) -i )*1.0/(nChangePoint-nStopPoint);
  503. xPlan[i].x = xold + fRatio*fMove*cos(xPlan[i].hdg - M_PI/2.0);
  504. xPlan[i].y = yold + fRatio*fMove*sin(xPlan[i].hdg - M_PI/2.0);
  505. xPlan[i].mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft + fRatio*fMove;
  506. }
  507. return;
  508. }
  509. #ifdef TESTSPEEDPLAN
  510. #include <math.h>
  511. #include <limits>
  512. double valuemin(double a,double b)
  513. {
  514. if(a<b)return a;
  515. return b;
  516. }
  517. int getPlanSpeed(std::vector<iv::GPSData> MapTrace)
  518. {
  519. int mode0to5count=0,mode0to18count=0,mode0to5countSum=0,mode0to18countSum=0,mode18count=0,mode18countSum=0,mode0to5flash=0,mode18flash=0;
  520. double straightSpeed=40;
  521. double straightCurveSpeed=30;
  522. double Curve_SmallSpeed=15;
  523. double Curve_LargeSpeed=8;
  524. std::vector<std::vector<double>> doubledata;
  525. doubledata.clear();
  526. for (int i = 0; i < MapTrace.size(); i++) { // 1225/14:25
  527. std::vector<double> temp;
  528. temp.clear();
  529. temp.push_back(0);temp.push_back(0);temp.push_back(0);temp.push_back(0);temp.push_back(0);//先push四个空量,然后就可以给量赋值了
  530. doubledata.push_back(temp);
  531. doubledata[i][0] = MapTrace.at(i)->gps_x;
  532. doubledata[i][1] = MapTrace.at(i)->gps_y;
  533. doubledata[i][2] = (MapTrace.at(i)->ins_heading_angle) / 180 * M_PI;
  534. doubledata[i][3]=0;
  535. doubledata[i][4]=0;
  536. }
  537. for(int i=0;i<doubledata.size();i++)
  538. {
  539. if((MapTrace[i]->mfCurvature>-0.02)&&(MapTrace[i]->mfCurvature<0.02)){
  540. MapTrace[i]->roadMode=5;
  541. }else if(((MapTrace[i]->mfCurvature>=0.02)&&(MapTrace[i]->mfCurvature<=0.16))||((MapTrace[i]->mfCurvature>=-0.16)&&(MapTrace[i]->mfCurvature<=-0.02))){
  542. MapTrace[i]->roadMode=18;
  543. }else if(((MapTrace[i]->mfCurvature>0.16))||((MapTrace[i]->mfCurvature<-0.16))){
  544. MapTrace[i]->roadMode=14;
  545. }
  546. }
  547. for(int i=0;i<MapTrace.size();i++)
  548. {
  549. if(MapTrace[i]->roadMode==0){
  550. doubledata[i][4]=straightSpeed;
  551. mode0to5count++;
  552. //mode0to18count++;
  553. mode18count=0;
  554. mode0to5flash=mode0to5count;
  555. }else if(MapTrace[i]->roadMode==5){
  556. doubledata[i][4]=straightCurveSpeed;
  557. mode0to5count++;
  558. //mode0to18count++;
  559. mode18count=0;
  560. mode0to5flash=mode0to5count;
  561. }else if(MapTrace[i]->roadMode==18){
  562. mode0to5countSum=mode0to5count;
  563. doubledata[i][4]=Curve_SmallSpeed;
  564. double brake_distance_double=(pow((straightCurveSpeed/3.6),2)-pow((Curve_SmallSpeed/3.6),2))*10/0.6;
  565. int brake_distance=(int)brake_distance_double;
  566. int step_count=0;
  567. if((i>brake_distance)&&(mode0to5countSum>brake_distance))
  568. {
  569. double step_speed=(straightCurveSpeed-Curve_SmallSpeed)/brake_distance;
  570. for(int j=i;j>i-brake_distance;j--){
  571. doubledata[j][4]=valuemin((Curve_SmallSpeed+step_count*step_speed),straightCurveSpeed);
  572. step_count++;
  573. }
  574. }else if(mode0to5countSum>0){
  575. for(int j=i;j>=i-mode0to5countSum;j--){
  576. doubledata[j][4]=Curve_SmallSpeed;
  577. step_count++;
  578. }
  579. }else{
  580. doubledata[i][4]=Curve_SmallSpeed;
  581. }
  582. mode0to5count=0;
  583. //mode0to18count++;
  584. mode18count++;
  585. mode18flash=mode18count;
  586. }else if(MapTrace[i]->roadMode==14){
  587. mode0to18countSum=mode0to5flash+mode18flash;
  588. mode18countSum=mode18count;
  589. double brake_distanceLarge_double=(pow((Curve_SmallSpeed/3.6),2)-pow((Curve_LargeSpeed/3.6),2))*10/0.6;
  590. double brake_distance0to18_double=(pow((straightCurveSpeed/3.6),2)-pow((Curve_LargeSpeed/3.6),2))*10/0.6;
  591. int brake_distanceLarge=(int)brake_distanceLarge_double;
  592. int brake_distance0to18=(int)brake_distance0to18_double;
  593. int step_count=0;
  594. doubledata[i][4]=Curve_LargeSpeed;
  595. if(mode18countSum>brake_distanceLarge)
  596. {
  597. double step_speed=(Curve_SmallSpeed-Curve_LargeSpeed)/brake_distanceLarge;
  598. for(int j=i;j>i-brake_distanceLarge;j--){
  599. doubledata[j][4]=valuemin((Curve_LargeSpeed+step_count*step_speed),Curve_SmallSpeed);
  600. step_count++;
  601. }
  602. }else if(mode0to18countSum>brake_distance0to18){
  603. double step_speed=(straightCurveSpeed-Curve_LargeSpeed)/brake_distance0to18;
  604. for(int j=i;j>i-brake_distance0to18;j--){
  605. doubledata[j][4]=valuemin((Curve_LargeSpeed+step_count*step_speed),straightCurveSpeed);
  606. step_count++;
  607. }
  608. }else{
  609. doubledata[i][4]=Curve_LargeSpeed;
  610. }
  611. mode0to5count=0;
  612. mode18count=0;
  613. mode0to5flash=0;
  614. mode18flash=0;
  615. }
  616. }
  617. return 0;
  618. }
  619. #endif
  620. void SetPlan(xodrobj xo)
  621. {
  622. double x_src,y_src,x_dst,y_dst;
  623. CalcXY(glat0,glon0,ghead0,xo.flatsrc,xo.flonsrc,x_src,y_src);
  624. CalcXY(glat0,glon0,ghead0,xo.flat,xo.flon,x_dst,y_dst);
  625. std::vector<PlanPoint> xPlan;
  626. double s;
  627. // x_src = -5;y_src = 6;
  628. // x_dst = -60;y_src = -150;
  629. int nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,(90 - xo.fhgdsrc)*M_PI/180.0,x_dst,y_dst,s,30.0,100.0,xo.lane,xPlan);
  630. if(nRtn < 0)
  631. {
  632. qDebug("plan fail.");
  633. return;
  634. }
  635. int i;
  636. int nSize = xPlan.size();
  637. if(gbSideLaneEnable)
  638. {
  639. CalcLaneSide(xPlan);
  640. }
  641. else
  642. {
  643. if(gbSideEnable)
  644. {
  645. CalcSide(xPlan);
  646. }
  647. }
  648. if(nSize<1)
  649. {
  650. qDebug("plan fail.");
  651. return;
  652. }
  653. PlanPoint xLastPoint = xPlan[nSize -1];
  654. for(i=0;i<600;i++)
  655. {
  656. PlanPoint pp = xLastPoint;
  657. double fdis = 0.1*(i+1);
  658. pp.mS = pp.mS + i*0.1;
  659. pp.x = pp.x + fdis * cos(pp.hdg);
  660. pp.y = pp.y + fdis * sin(pp.hdg);
  661. pp.nSignal = 23;
  662. if(gbExtendMap)
  663. {
  664. xPlan.push_back(pp);
  665. }
  666. }
  667. iv::map::tracemap xtrace;
  668. nSize = xPlan.size();
  669. std::vector<iv::GPSData> mapdata;
  670. //maptrace
  671. QFile xfile;
  672. QString strpath;
  673. strpath = getenv("HOME");
  674. strpath = strpath + "/map/maptrace.txt";
  675. xfile.setFileName(strpath);
  676. xfile.open(QIODevice::ReadWrite);
  677. //maptrace_add
  678. QFile xfile_1;
  679. QString strpath_1;
  680. strpath_1 = getenv("HOME");
  681. strpath_1 = strpath_1 + "/map/mapadd.txt";
  682. xfile_1.setFileName(strpath_1);
  683. xfile_1.open(QIODevice::ReadWrite);
  684. for(i=0;i<nSize;i++)
  685. {
  686. iv::map::mappoint * pmappoint = xtrace.add_point();
  687. double gps_lon,gps_lat,gps_lon_avoidleft,gps_lat_avoidleft,gps_lat_avoidright,gps_lon_avoidright,gps_heading;
  688. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,gps_lat,
  689. gps_lon,gps_heading);
  690. CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
  691. gps_lat_avoidleft,gps_lon_avoidleft);
  692. CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
  693. gps_lat_avoidright,gps_lon_avoidright);
  694. pmappoint->set_gps_lat(gps_lat);
  695. pmappoint->set_gps_lat_avoidleft(gps_lat_avoidleft);
  696. pmappoint->set_gps_lat_avoidright(gps_lat_avoidright);
  697. pmappoint->set_gps_lng(gps_lon);
  698. pmappoint->set_gps_lat_avoidleft(gps_lat_avoidleft);
  699. pmappoint->set_gps_lng_avoidright(gps_lon_avoidright);
  700. pmappoint->set_ins_heading_angle(gps_heading);
  701. double gps_x,gps_y,gps_x_avoidleft,gps_y_avoidleft,gps_x_avoidright,gps_y_avoidright;
  702. GaussProjCal(gps_lon,gps_lat,&gps_x,&gps_y);
  703. GaussProjCal(gps_lon_avoidleft,gps_lat_avoidleft,&gps_x_avoidleft,&gps_y_avoidleft);
  704. GaussProjCal(gps_lon_avoidright,gps_lat_avoidright,&gps_x_avoidright,&gps_y_avoidright);
  705. pmappoint->set_gps_x(gps_x);
  706. pmappoint->set_gps_x_avoidleft(gps_x_avoidleft);
  707. pmappoint->set_gps_x_avoidright(gps_x_avoidright);
  708. pmappoint->set_gps_y(gps_y);
  709. pmappoint->set_gps_y_avoidleft(gps_y_avoidleft);
  710. pmappoint->set_gps_y_avoidright(gps_y_avoidright);
  711. pmappoint->set_speed(xPlan[i].speed);
  712. pmappoint->set_index(i);
  713. pmappoint->set_roadori(xPlan[i].mnLaneori);
  714. pmappoint->set_roadsum(xPlan[i].mnLaneTotal);
  715. pmappoint->set_mfdistolaneleft(xPlan[i].mfDisToLaneLeft);
  716. pmappoint->set_mfdistoroadleft(xPlan[i].mfDisToRoadLeft);
  717. pmappoint->set_mflanewidth(xPlan[i].mWidth);
  718. pmappoint->set_mfroadwidth(xPlan[i].mfRoadWidth);
  719. pmappoint->set_mbinlaneavoid(xPlan[i].bInlaneAvoid);
  720. iv::GPSData data(new iv::GPS_INS);
  721. data->roadMode = 0;
  722. // std::cout<<"i:"<<i<<" lr:"<<xPlan[i].nlrchange<<std::endl;
  723. if(xPlan[i].nlrchange == 1)
  724. {
  725. data->roadMode = 14;
  726. }
  727. if(xPlan[i].nlrchange == 2)
  728. {
  729. data->roadMode = 15;
  730. }
  731. if(i>50)
  732. {
  733. if((xPlan[i-1].nlrchange == 0)&&(xPlan[i].nlrchange != 0))
  734. {
  735. int j;
  736. for(j=(i-1);j>=(i-50);j--)
  737. {
  738. if(xPlan[i].nlrchange == 1)
  739. {
  740. mapdata[j]->roadMode = 14;
  741. }
  742. if(xPlan[i].nlrchange == 2)
  743. {
  744. mapdata[j]->roadMode = 15;
  745. }
  746. if(j <=0)break;
  747. }
  748. }
  749. }
  750. data->gps_lat = gps_lat;
  751. data->gps_lat_avoidleft = gps_lat_avoidleft;
  752. data->gps_lat_avoidright = gps_lat_avoidright;
  753. data->gps_lng = gps_lon;
  754. data->gps_lng_avoidleft = gps_lon_avoidleft;
  755. data->gps_lng_avoidright = gps_lon_avoidright;
  756. data->ins_heading_angle = gps_heading;
  757. data->gps_x = gps_x;
  758. data->gps_x_avoidleft = gps_x_avoidleft;
  759. data->gps_x_avoidright = gps_x_avoidright;
  760. data->gps_y = gps_y;
  761. data->gps_y_avoidleft = gps_y_avoidleft;
  762. data->gps_y_avoidright = gps_y_avoidright;
  763. pmappoint->set_mbnoavoid(xPlan[i].mbNoavoid);
  764. pmappoint->set_mfcurvature(xPlan[i].mfCurvature);
  765. // CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  766. // data->gps_lng,data->ins_heading_angle);
  767. // CalcLatLon(glat0,glon0,xPlan[i].mx_left,xPlan[i].my_left,
  768. // data->gps_lat_avoidleft,data->gps_lng_avoidleft);
  769. // CalcLatLon(glat0,glon0,xPlan[i].mx_right,xPlan[i].my_right,
  770. // data->gps_lat_avoidright,data->gps_lng_avoidright);
  771. data->index = i;
  772. data->speed = xPlan[i].speed;
  773. // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  774. // GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  775. // GaussProjCal(data->gps_lng_avoidleft,data->gps_lat_avoidleft,&data->gps_x_avoidleft,&data->gps_y_avoidleft);
  776. // GaussProjCal(data->gps_lng_avoidright,data->gps_lat_avoidright,&data->gps_x_avoidright,&data->gps_y_avoidright);
  777. givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  778. data->gps_lng,data->ins_heading_angle);
  779. data->roadOri = xPlan[i].mnLaneori;
  780. data->roadSum = xPlan[i].mnLaneTotal;
  781. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  782. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  783. data->mfLaneWidth = xPlan[i].mWidth;
  784. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  785. data->mbInLaneAvoid = xPlan[i].bInlaneAvoid;
  786. if(xPlan[i].mbBoringRoad)
  787. {
  788. data->roadOri = 0;
  789. data->roadSum = 2;
  790. pmappoint->set_roadori(0);
  791. pmappoint->set_roadsum(2);
  792. }
  793. data->mbnoavoid = xPlan[i].mbNoavoid;
  794. if(data->mbnoavoid)
  795. {
  796. qDebug("no avoid i = %d",i);
  797. }
  798. data->mfCurvature = xPlan[i].mfCurvature;
  799. data->mode2 = xPlan[i].nSignal;
  800. if(data->mode2 == 3000)
  801. {
  802. int k;
  803. for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
  804. {
  805. if(k<0)break;
  806. if((mapdata.at(k)->mode2 != -1)&&(mapdata.at(k)->mode2 !=3000))
  807. {
  808. continue;
  809. }
  810. mapdata.at(k)->mode2 = 3000;
  811. }
  812. }
  813. if(data->mode2 == 1000001)
  814. {
  815. int k;
  816. for(k=(mapdata.size()-1);k>(mapdata.size()-10);k--)
  817. {
  818. if(k<0)break;
  819. if((mapdata.at(k)->mode2 != -1)&&(mapdata.at(k)->mode2 !=1000001))
  820. {
  821. continue;
  822. }
  823. mapdata.at(k)->mode2 = 1000001;
  824. }
  825. }
  826. pmappoint->set_mode2(data->mode2);
  827. pmappoint->set_rel_x(xPlan[i].x);
  828. pmappoint->set_rel_y(xPlan[i].y);
  829. pmappoint->set_rel_z(0);
  830. pmappoint->set_rel_yaw(xPlan[i].hdg);
  831. pmappoint->set_laneid(-1);
  832. pmappoint->set_roadid(xPlan[i].nRoadID);
  833. #ifdef BOAVOID
  834. if(isboringroad(xPlan[i].nRoadID))
  835. {
  836. const int nrangeavoid = 300;
  837. if((i+(nrangeavoid + 10))<nSize)
  838. {
  839. double fhdg1 = xPlan[i].hdg;
  840. bool bavoid = true;
  841. // int k;
  842. // for(k=0;k<=10;k++)
  843. // {
  844. // double fhdg5 = xPlan[i+nrangeavoid*k/10].hdg;
  845. // double fhdgdiff1 = fhdg5 - fhdg1;
  846. // while(fhdgdiff1<0)fhdgdiff1 = fhdgdiff1 + 2.0*M_PI;
  847. // if((fhdgdiff1>(M_PI/3.0))&&(fhdgdiff1<(5.0*M_PI/3.0)))
  848. // {
  849. // bavoid = false;
  850. // break;
  851. // }
  852. // }
  853. if(bavoid)
  854. {
  855. data->roadSum = 2;
  856. data->roadOri = 0;
  857. }
  858. }
  859. else
  860. {
  861. int a = 1;
  862. a++;
  863. }
  864. }
  865. #endif
  866. mapdata.push_back(data);
  867. // char strline[255];
  868. // // snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%11.3f\t%d\t%d\t%d\t%d\t%d\t%d\t%11.7f\n",
  869. // // i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,data->roadOri,data->roadSum,data->mode2,data->mfCurvature);
  870. // snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\t%d\n",
  871. // i,data->gps_lng,data->gps_lat,0,0,data->ins_heading_angle,0,0,data->roadSum,data->roadOri,data->mode2);
  872. // xfile.write(strline);
  873. }
  874. for(int j=0;j<nSize;j++)
  875. {
  876. char strline[255];
  877. snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\n",
  878. j,mapdata.at(j)->gps_lng,mapdata.at(j)->gps_lat,0,0,mapdata.at(j)->ins_heading_angle,0,0,mapdata.at(j)->roadSum,mapdata.at(j)->roadOri);
  879. xfile.write(strline);
  880. //mapttrace1
  881. char strline_1[255];
  882. snprintf(strline_1,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\t%d\n",
  883. j,mapdata.at(j)->gps_lng,mapdata.at(j)->gps_lat,0,0,mapdata.at(j)->ins_heading_angle,0,0,mapdata.at(j)->roadSum,mapdata.at(j)->roadOri,mapdata.at(j)->mode2);
  884. xfile_1.write(strline_1);
  885. }
  886. xfile.close();
  887. xfile_1.close();
  888. ShareMap(mapdata);
  889. #ifdef TESTSPEEDPLAN
  890. getPlanSpeed(mapdata);
  891. #endif
  892. ShareMapGlobal(xPlan);
  893. int nnewmapsize = xtrace.ByteSize();
  894. std::shared_ptr<char> str_ptr = std::shared_ptr<char>(new char[nnewmapsize]);
  895. if(xtrace.SerializeToArray(str_ptr.get(),nnewmapsize))
  896. {
  897. iv::modulecomm::ModuleSendMsg(gpanewtrace ,str_ptr.get(),nnewmapsize);
  898. }
  899. else
  900. {
  901. std::cout<<" new trace map serialize fail."<<std::endl;
  902. }
  903. s = 1;
  904. }
  905. void MultiStationPlan(iv::v2x::v2x * pxv2x,double fsrclat,double fsrclon,double fsrcheading,int nlane)
  906. {
  907. std::vector<PlanPoint> xPlan;
  908. int i;
  909. double fLastHdg = 0;
  910. int ndeflane =nlane;
  911. for(i=0;i<pxv2x->stgps_size();i++)
  912. {
  913. double x_src,y_src,x_dst,y_dst;
  914. if(i==0)
  915. {
  916. CalcXY(glat0,glon0,ghead0,fsrclat,fsrclon,x_src,y_src);
  917. }
  918. else
  919. {
  920. CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i-1).lat(),pxv2x->stgps(i-1).lon(),x_src,y_src);
  921. }
  922. CalcXY(glat0,glon0,ghead0,pxv2x->stgps(i).lat(),pxv2x->stgps(i).lon(),x_dst,y_dst);
  923. std::vector<PlanPoint> xPlanPart;
  924. double s;
  925. // x_src = -5;y_src = 6;
  926. // x_dst = -60;y_src = -150;
  927. int nRtn = -1;
  928. if(i==0)
  929. {
  930. nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,(90 - fsrcheading)*M_PI/180.0,x_dst,y_dst,s,30.0,100.0,ndeflane,xPlanPart);
  931. }
  932. else
  933. {
  934. nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,fLastHdg,x_dst,y_dst,s,30.0,100.0,ndeflane,xPlanPart);
  935. }
  936. if(nRtn < 0)
  937. {
  938. qDebug("plan fail.");
  939. return;
  940. }
  941. int j;
  942. for(j=0;j<xPlanPart.size();j++)xPlan.push_back(xPlanPart.at(j));
  943. fLastHdg = xPlanPart.at(xPlanPart.size()-1).hdg;
  944. }
  945. int nSize = xPlan.size();
  946. std::vector<iv::GPSData> mapdata;
  947. QFile xfile;
  948. QString strpath;
  949. strpath = getenv("HOME");
  950. strpath = strpath + "/map/maptrace.txt";
  951. xfile.setFileName(strpath);
  952. xfile.open(QIODevice::ReadWrite);
  953. for(i=0;i<nSize;i++)
  954. {
  955. iv::GPSData data(new iv::GPS_INS);
  956. CalcLatLon(glat0,glon0,ghead0,xPlan[i].x,xPlan[i].y,xPlan[i].hdg,data->gps_lat,
  957. data->gps_lng,data->ins_heading_angle);
  958. data->index = i;
  959. data->speed = xPlan[i].speed;
  960. // ZBGaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  961. GaussProjCal(data->gps_lng,data->gps_lat,&data->gps_x,&data->gps_y);
  962. givlog->verbose(" %d %11.7f %11.7f %11.3f ",i,data->gps_lat,
  963. data->gps_lng,data->ins_heading_angle);
  964. // data->roadSum = 1;
  965. // data->roadMode = 0;
  966. // data->roadOri = 0;
  967. // if(xPlan[i].lanmp == -1)data->roadMode = 15;
  968. // if(xPlan[i].lanmp == 1)data->roadMode = 14;
  969. data->roadOri = xPlan[i].mnLaneori;
  970. data->roadSum = xPlan[i].mnLaneTotal;
  971. data->mfDisToLaneLeft = xPlan[i].mfDisToLaneLeft;
  972. data->mfDisToRoadLeft = xPlan[i].mfDisToRoadLeft;
  973. data->mfLaneWidth = xPlan[i].mWidth;
  974. data->mfRoadWidth = xPlan[i].mfRoadWidth;
  975. data->mode2 = xPlan[i].nSignal;
  976. if(data->mode2 == 3000)
  977. {
  978. int k;
  979. for(k=(mapdata.size()-1);k>(mapdata.size()-150);k--)
  980. {
  981. if(k<0)break;
  982. mapdata.at(k)->mode2 = 3000;
  983. }
  984. }
  985. mapdata.push_back(data);
  986. char strline[255];
  987. snprintf(strline,255,"%d\t%11.7f\t%11.7f\t%d\t%d\t%11.3f\t%d\t%d\t%d\t%d\n",
  988. i,data->gps_lng,data->gps_lat,0,data->ins_heading_angle,0,0,0,0,0);
  989. xfile.write(strline);
  990. }
  991. xfile.close();
  992. ShareMap(mapdata);
  993. }
  994. void ListenCmd(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  995. {
  996. if(nSize<sizeof(xodrobj))
  997. {
  998. std::cout<<"ListenCmd small."<<std::endl;
  999. return;
  1000. }
  1001. xodrobj xo;
  1002. memcpy(&xo,strdata,sizeof(xodrobj));
  1003. givlog->debug("lat is %f", xo.flat);
  1004. xo.fhgdsrc = gsrc.fhgdsrc;
  1005. xo.flatsrc = gsrc.flatsrc;
  1006. xo.flonsrc = gsrc.flonsrc;
  1007. SetPlan(xo);
  1008. }
  1009. void ListenV2X(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1010. {
  1011. iv::v2x::v2x xv2x;
  1012. if(!xv2x.ParseFromArray(strdata,nSize))
  1013. {
  1014. givlog->warn("ListernV2X Parse Error.");
  1015. std::cout<<"ListenV2X Parse Error."<<std::endl;
  1016. return;
  1017. }
  1018. if(xv2x.stgps_size()<1)
  1019. {
  1020. givlog->debug("ListenV2X no gps station.");
  1021. std::cout<<"ListenV2X no gps station."<<std::endl;
  1022. return;
  1023. }
  1024. MultiStationPlan(&xv2x,gsrc.flatsrc,gsrc.flonsrc,gsrc.fhgdsrc,1);
  1025. }
  1026. void ListenSrc(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1027. {
  1028. if(nSize<sizeof(xodrobj))
  1029. {
  1030. givlog->warn("ListenSrc small");
  1031. std::cout<<"ListenSrc small."<<std::endl;
  1032. return;
  1033. }
  1034. memcpy(&gsrc,strdata,sizeof(xodrobj));
  1035. givlog->debug("src hdg is %f", gsrc.fhgdsrc);
  1036. std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
  1037. }
  1038. void UpdateGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  1039. {
  1040. iv::gps::gpsimu xgpsimu;
  1041. if(!xgpsimu.ParseFromArray(strdata,nSize))
  1042. {
  1043. givlog->warn("ADCIntelligentVehicle::UpdateGPSIMU parse error. nSize is %d",nSize);
  1044. return;
  1045. }
  1046. xodrobj xo;
  1047. xo.fhgdsrc = xgpsimu.heading();
  1048. xo.flatsrc = xgpsimu.lat();
  1049. xo.flonsrc = xgpsimu.lon();
  1050. gsrc = xo;
  1051. givlog->debug("src hdg is %f", gsrc.fhgdsrc);
  1052. std::cout<<"src hdg is "<<gsrc.fhgdsrc<<std::endl;
  1053. }
  1054. void ExitFunc()
  1055. {
  1056. // gApp->quit();
  1057. iv::modulecomm::Unregister(gpasimple);
  1058. iv::modulecomm::Unregister(gpav2x);
  1059. iv::modulecomm::Unregister(gpagps);
  1060. iv::modulecomm::Unregister(gpasrc);
  1061. iv::modulecomm::Unregister(gpmap);
  1062. iv::modulecomm::Unregister(gpa);
  1063. std::cout<<"driver_map_xodrload exit."<<std::endl;
  1064. gApp->quit();
  1065. std::this_thread::sleep_for(std::chrono::milliseconds(100));
  1066. // std::this_thread::sleep_for(std::chrono::milliseconds(900));
  1067. }
  1068. void signal_handler(int sig)
  1069. {
  1070. if(sig == SIGINT)
  1071. {
  1072. ExitFunc();
  1073. }
  1074. }
  1075. void ProcROIReq(std::shared_ptr<char> pstr_req,const int nreqsize,std::shared_ptr<char> & pstr_res,int & nressize)
  1076. {
  1077. (void)pstr_req;
  1078. (void)nreqsize;
  1079. std::shared_ptr<iv::roi::request> pstr_roireq = std::shared_ptr<iv::roi::request>(new iv::roi::request);
  1080. if(pstr_roireq->ParseFromArray(pstr_req.get(),nreqsize))
  1081. {
  1082. std::shared_ptr<iv::roi::resultarray> pstr_roires;
  1083. gsrx.GetROI(pstr_roireq,pstr_roires);
  1084. int nbytesize = pstr_roires->ByteSize();
  1085. pstr_res = std::shared_ptr<char>(new char[nbytesize]);
  1086. if(pstr_roires->SerializeToArray(pstr_res.get(),nbytesize))
  1087. {
  1088. nressize = nbytesize;
  1089. std::cout<<"return res."<<std::endl;
  1090. return;
  1091. }
  1092. else
  1093. {
  1094. std::cout<<" ProcROIReq fail serizlizetoarray"<<std::endl;
  1095. }
  1096. }
  1097. else
  1098. {
  1099. std::cout<<" ProcROIReq parse pstr_req fail."<<std::endl;
  1100. return;
  1101. }
  1102. }
  1103. int main(int argc, char *argv[])
  1104. {
  1105. showversion("driver_map_xodrload");
  1106. QCoreApplication a(argc, argv);
  1107. gApp = &a;
  1108. RegisterIVBackTrace();
  1109. gfault = new iv::Ivfault("driver_map_xodrload");
  1110. givlog = new iv::Ivlog("driver_map_xodrload");
  1111. std::string strmapth,strparapath;
  1112. if(argc<3)
  1113. {
  1114. // strmapth = "./map.xodr";
  1115. strmapth = getenv("HOME");
  1116. strmapth = strmapth + "/map/map.xodr";
  1117. // strmapth = "/home/yuchuli/1226.xodr";
  1118. strparapath = "./driver_map_xodrload.xml";
  1119. }
  1120. else
  1121. {
  1122. strmapth = argv[1];
  1123. strparapath = argv[2];
  1124. }
  1125. iv::xmlparam::Xmlparam xp(strparapath);
  1126. xp.GetParam(std::string("he"),std::string("1"));
  1127. std::string strlat0 = xp.GetParam("lat0","39");
  1128. std::string strlon0 = xp.GetParam("lon0","117.0");
  1129. std::string strhdg0 = xp.GetParam("hdg0","360.0");
  1130. std::string strgpsmsg = xp.GetParam("gpsmsg","hcp2_gpsimu");
  1131. std::string strv2xmsg = xp.GetParam("v2xmsg","v2x");
  1132. std::string strvehiclewidth = xp.GetParam("vehiclewidth","2.0");
  1133. std::string strextendmap = xp.GetParam("extendmap","false");
  1134. std::string strsideenable = xp.GetParam("sideenable","false");
  1135. std::string strsidelaneenable = xp.GetParam("sidelaneenable","false");
  1136. gstrcdata = xp.GetParam("cdata","");
  1137. std::cout<<" cdata: "<<gstrcdata.data()<<std::endl;
  1138. #ifdef USE_TMERS
  1139. if(gstrcdata.length()>3)
  1140. {
  1141. C = proj_context_create();//创建多线程,由于本示例为单线程,此处为展示作用
  1142. P = proj_create_crs_to_crs (C,
  1143. "WGS84",
  1144. "+proj=tmerc +ellps=WGS84 +datum=WGS84 +units=m +lat_0=28.3252659663377 +lon_0=117.810536087614 +no_defs", /* or EPSG:32632 */
  1145. NULL);
  1146. // P = proj_create(C,"+proj=tmerc +ellps=WGS84 +datum=WGS84 +units=m +lat_0=28.3252659663377 +lon_0=117.810536087614 +no_defs");
  1147. if (0 == P) {
  1148. std::cout << "Failed to create transformation object." << stderr << std::endl;
  1149. return 1;
  1150. }//如果P中两个投影的字符串不符合proj定义,提示转换失败
  1151. norm = proj_normalize_for_visualization(C, P);
  1152. if (0 == norm) {
  1153. fprintf(stderr, "Failed to normalize transformation object.\n");
  1154. return 1;
  1155. }
  1156. proj_destroy(P);
  1157. P = norm;
  1158. }
  1159. #endif
  1160. glat0 = atof(strlat0.data());
  1161. glon0 = atof(strlon0.data());
  1162. ghead0 = atof(strhdg0.data());
  1163. gvehiclewidth = atof(strvehiclewidth.data());
  1164. if(strextendmap == "true")
  1165. {
  1166. gbExtendMap = true;
  1167. }
  1168. else
  1169. {
  1170. gbExtendMap = false;
  1171. }
  1172. if(strsideenable == "true")
  1173. {
  1174. gbSideEnable = true;
  1175. }
  1176. if(strsidelaneenable == "true")
  1177. {
  1178. gbSideLaneEnable = true;
  1179. }
  1180. LoadXODR(strmapth);
  1181. iv::service::Server serviceroi("ServiceROI",ProcROIReq);
  1182. (void)serviceroi;
  1183. gpmap = iv::modulecomm::RegisterSend("tracemap",20000000,1);
  1184. gpasimple = iv::modulecomm::RegisterSend("simpletrace",100000,1);
  1185. gpanewtrace = iv::modulecomm::RegisterSend("newtracemap",20000000,1);
  1186. gpamapglobal = iv::modulecomm::RegisterSend("mapglobal",20000000,1);
  1187. gpa = iv::modulecomm::RegisterRecv("xodrreq",ListenCmd);
  1188. gpasrc =iv::modulecomm::RegisterRecv("xodrsrc",ListenSrc);
  1189. gpagps = iv::modulecomm::RegisterRecv(strgpsmsg.data(),UpdateGPSIMU);
  1190. gpav2x = iv::modulecomm::RegisterRecv(strv2xmsg.data(),ListenV2X);
  1191. double x_src,y_src,x_dst,y_dst;
  1192. x_src = -26;y_src = 10;
  1193. x_dst = -50;y_dst = -220;
  1194. x_src = 0;y_src = 0;
  1195. x_dst = -23;y_dst = -18;
  1196. x_dst = 21;y_dst =-21;
  1197. x_dst =5;y_dst = 0;
  1198. x_src = -20; y_src = -1000;
  1199. x_dst = 900; y_dst = -630;
  1200. // x_dst = 450; y_dst = -640;
  1201. // x_dst = -190; y_dst = -690;
  1202. // x_src = 900; y_src = -610;
  1203. // x_dst = -100; y_dst = -680;
  1204. std::vector<PlanPoint> xPlan;
  1205. double s;
  1206. // int nRtn = MakePlan(gpxd,&mxodr,x_src,y_src,3.14,x_dst,y_dst,s,30.0,100.0,1,xPlan);
  1207. // ToGPSTrace(xPlan);
  1208. // double lat = 39.1443880;
  1209. // double lon = 117.0812543;
  1210. // xodrobj xo;
  1211. // xo.fhgdsrc = 340;
  1212. // xo.flatsrc = lat; xo.flonsrc = lon;
  1213. // xo.flat = 39.1490196;
  1214. // xo.flon = 117.0806979;
  1215. // xo.lane = 1;
  1216. // SetPlan(xo);
  1217. // void * pivexit = iv::ivexit::RegIVExitCall(ExitFunc);
  1218. signal(SIGINT,signal_handler);
  1219. int nrc = a.exec();
  1220. std::cout<<"driver_map_xodr app exit. code :"<<nrc<<std::endl;
  1221. return nrc;
  1222. }