roadviewitem.cpp 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944
  1. #include "roadviewitem.h"
  2. #include <math.h>
  3. #include "geofit.h"
  4. #include <QtWidgets>
  5. #include <QFont>
  6. roadviewitem::roadviewitem(Road * pRoad)
  7. {
  8. mpRoad = pRoad;
  9. mbNeedCalc = true;
  10. }
  11. QRectF roadviewitem::boundingRect() const
  12. {
  13. // qDebug("ratio is %f",mfratio);
  14. // return QRectF((mfxmin - mfwidth - 15)*mfratio,(mfymin-mfwidth-15)*mfratio,(mfxmax - mfxmin + 2.0*mfwidth+30)*mfratio,
  15. // (mfymax - mfymin+2.0*mfwidth+30)*mfratio);
  16. return QRectF( - 10000,-10000 ,20000,
  17. 20000);
  18. // return QRectF(-10000,-10000,20000,20000);
  19. // float fwidth = mfwidth * mfratio;
  20. // return QRectF(mfxmin - fwidth - 15,mfymin-fwidth-15,mfxmax - mfxmin + 2.0*fwidth+30,
  21. // mfymax - mfymin+2.0*fwidth+30);
  22. return QRectF(mfxmin - 10000,mfymin-10000,mfxmax - mfxmin + 20000,
  23. mfymax - mfymin+20000);
  24. // return QRectF(mfxmin - fwidth - 15,mfymin-fwidth-15,mfxmax - mfxmin + 2.0*fwidth+30,mfymax - mfymin+2.0*fwidth+30);
  25. // return QRectF(-10000,-10000,20000,20000);
  26. }
  27. void roadviewitem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
  28. {
  29. (void)option;
  30. int i;
  31. // if((mfratio/mfoldcalratio>3.0)||(mfratio/mfoldcalratio<0.3))
  32. // {
  33. // mbNeedCalc = true;
  34. // }
  35. if(mfratio != mfoldcalratio)mbNeedCalc = true;
  36. // qDebug("painter");
  37. Q_UNUSED(option);
  38. Q_UNUSED(widget);
  39. if(mbNeedCalc)
  40. {
  41. CalcLine();
  42. CalcLane();
  43. }
  44. painter->setPen(Qt::NoPen);
  45. // painter->setBrush(Qt::darkGray);
  46. // painter->drawRect(0,0,mnlen,mnwidth*mfratio);
  47. if(mbShowLine)
  48. {
  49. if(mbMark)painter->setBrush(Qt::red);
  50. else
  51. painter->setBrush(Qt::white);
  52. for(i=0;i<mvectorline.size();i++)
  53. {
  54. painter->drawPolygon(mvectorline[i].mPoints,4);
  55. }
  56. }
  57. if(mbShowLane)
  58. {
  59. painter->setBrush(Qt::darkGray);
  60. int nsize = mvectorlaneview.size();
  61. for(i=0;i<nsize;i++)
  62. {
  63. switch (mvectorlaneview[i].ntype) {
  64. case 2:
  65. painter->setBrush(Qt::darkGray);
  66. break;
  67. case 8:
  68. painter->setBrush(Qt::red);
  69. break;
  70. case 9:
  71. painter->setBrush(QColor(0xB2,0xB2,0xD6));
  72. break;
  73. default:
  74. painter->setBrush(Qt::darkGreen);
  75. break;
  76. }
  77. painter->drawPolygon(mvectorlaneview[i].mPoints,4);
  78. }
  79. }
  80. painter->setBrush(Qt::white);
  81. int nsize = mvectorlanemark.size();
  82. for(i=0;i<nsize;i++)
  83. {
  84. switch (mvectorlanemark[i].ncolor) {
  85. case 0:
  86. painter->setBrush(Qt::white);
  87. break;
  88. case 1:
  89. painter->setBrush(Qt::blue);
  90. break;
  91. case 2:
  92. painter->setBrush(Qt::green);
  93. break;
  94. case 3:
  95. painter->setBrush(Qt::red);
  96. break;
  97. case 4:
  98. painter->setBrush(Qt::white);
  99. break;
  100. case 5:
  101. painter->setBrush(Qt::yellow);
  102. break;
  103. case 6:
  104. painter->setBrush(Qt::yellow); //orange use yellow replace
  105. break;
  106. default:
  107. painter->setBrush(Qt::white);
  108. break;
  109. }
  110. painter->drawPolygon(mvectorlanemark[i].mPoints,4);
  111. painter->setBrush(Qt::white);
  112. }
  113. QPen pen;
  114. pen.setWidth(1);
  115. pen.setColor(Qt::white);
  116. painter->setPen(pen);
  117. QFont font = painter->font();
  118. font.setPixelSize(3);
  119. painter->setFont(font);
  120. if(mbShowRoadID)
  121. {
  122. painter->drawText(mtextx,mtexty,mpRoad->GetRoadId().data());
  123. }
  124. painter->setBrush(Qt::NoBrush);
  125. if(mbShowLine)
  126. {
  127. if(mbMark)
  128. {
  129. if(mvectorline.size()>0)
  130. {
  131. painter->drawEllipse(mvectorline[0].mstartx-1.5,mvectorline[0].mstarty-1.5,3,3);
  132. }
  133. }
  134. }
  135. // QPen pen;
  136. // pen.setWidth(1);
  137. // pen.setColor(Qt::white);
  138. // painter->setPen(pen);
  139. // for(i=0;i<mvectorline.size();i++)
  140. // {
  141. // painter->drawLine(mvectorline[i].mstartx,mvectorline[i].mstarty,
  142. // mvectorline[i].mendx,mvectorline[i].mendy);
  143. // }
  144. // painter->drawLine(1,0,mnlen-1,0);
  145. }
  146. bool roadviewitem::IsDrawMark(double s)
  147. {
  148. const double dotdis = 10.0;
  149. const double dotlen = 5.0;
  150. double y = fmod(s,dotdis);
  151. if(y>dotlen)return true;
  152. else
  153. {
  154. return false;
  155. }
  156. }
  157. void roadviewitem::CalcLane()
  158. {
  159. if(mbShowLane == false)return;
  160. int i,j;
  161. int nsize = mvectorline.size();
  162. mvectorlaneview.clear();
  163. mvectorlanemark.clear();
  164. double flmw = 0.15;
  165. for(i=0;i<mvectorlaneline.size();i++)
  166. {
  167. for(j=0;j<(mvectorlaneline[i].mvectorlanelinese.size()-1);j++)
  168. {
  169. std::vector<iv::LanePoint> xvepre = mvectorlaneline[i].mvectorlanelinese[j].mvectorlanepoint;
  170. std::vector<iv::LanePoint> xvenxt = mvectorlaneline[i].mvectorlanelinese[j+1].mvectorlanepoint;
  171. if((xvepre.size()<2)||(xvenxt.size()<2)||(xvenxt.size() != xvepre.size()))
  172. {
  173. continue;
  174. }
  175. int k;
  176. for(k=0;k<(xvepre.size()-1);k++)
  177. {
  178. iv::laneviewdata lv;
  179. lv.mPoints[0].setX(xvepre[k].mfX);
  180. lv.mPoints[0].setY(xvepre[k].mfY*(-1.0));
  181. lv.mPoints[1].setX(xvenxt[k].mfX);
  182. lv.mPoints[1].setY(xvenxt[k].mfY*(-1.0));
  183. lv.mPoints[2].setX(xvenxt[k+1].mfX);
  184. lv.mPoints[2].setY(xvenxt[k+1].mfY*(-1.0));
  185. lv.mPoints[3].setX(xvepre[k+1].mfX);
  186. lv.mPoints[3].setY(xvepre[k+1].mfY*(-1.0));
  187. if(xvepre[k].mnlane>0)lv.ntype = xvepre[k].mnlanetype;
  188. else lv.ntype = xvepre[k+1].mnlanetype;
  189. mvectorlaneview.push_back(lv);
  190. }
  191. }
  192. }
  193. for(i=0;i<mvectorlaneline.size();i++)
  194. {
  195. for(j=0;j<(mvectorlaneline[i].mvectorlanelinese.size()-1);j++)
  196. {
  197. std::vector<iv::LanePoint> xvepre = mvectorlaneline[i].mvectorlanelinese[j].mvectorlanepoint;
  198. std::vector<iv::LanePoint> xvenxt = mvectorlaneline[i].mvectorlanelinese[j+1].mvectorlanepoint;
  199. if((xvepre.size()<2)||(xvenxt.size()<2)||(xvenxt.size() != xvepre.size()))
  200. {
  201. continue;
  202. }
  203. int k;
  204. for(k=0;k<(xvepre.size());k++)
  205. {
  206. iv::lanemark lv;
  207. int nmarktype = xvepre[k].mnlanemarktype;
  208. if(nmarktype >= 0)
  209. {
  210. if(nmarktype<2)
  211. {
  212. if((nmarktype == 0)||(IsDrawMark(xvepre[k].mS)))
  213. {
  214. lv.mPoints[0].setX(xvepre[k].mfX + 0.5*flmw * cos(xvenxt[k].mfhdg - M_PI/2.0));
  215. lv.mPoints[0].setY((xvepre[k].mfY+0.5*flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
  216. lv.mPoints[1].setX(xvenxt[k].mfX+ 0.5*flmw * cos(xvepre[k].mfhdg - M_PI/2.0));
  217. lv.mPoints[1].setY((xvenxt[k].mfY+0.5*flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
  218. lv.mPoints[2].setX(xvenxt[k].mfX + 0.5*flmw * cos(xvenxt[k].mfhdg + M_PI/2.0));
  219. lv.mPoints[2].setY((xvenxt[k].mfY+0.5*flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
  220. lv.mPoints[3].setX(xvepre[k].mfX+ 0.5*flmw * cos(xvepre[k].mfhdg + M_PI/2.0));
  221. lv.mPoints[3].setY((xvepre[k].mfY+0.5*flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
  222. lv.ncolor = xvepre[k].mnlanecolor;
  223. mvectorlanemark.push_back(lv);
  224. }
  225. }
  226. else
  227. {
  228. if((nmarktype == 2)||(nmarktype == 3)||(IsDrawMark(xvepre[k].mS)))
  229. {
  230. lv.mPoints[0].setX(xvepre[k].mfX + flmw * cos(xvenxt[k].mfhdg + M_PI/2.0));
  231. lv.mPoints[0].setY((xvepre[k].mfY+flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
  232. lv.mPoints[1].setX(xvenxt[k].mfX+ flmw * cos(xvepre[k].mfhdg + M_PI/2.0));
  233. lv.mPoints[1].setY((xvenxt[k].mfY+flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
  234. lv.mPoints[2].setX(xvenxt[k].mfX + 2*flmw * cos(xvenxt[k].mfhdg + M_PI/2.0));
  235. lv.mPoints[2].setY((xvenxt[k].mfY+2*flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
  236. lv.mPoints[3].setX(xvepre[k].mfX+ 2*flmw * cos(xvepre[k].mfhdg + M_PI/2.0));
  237. lv.mPoints[3].setY((xvepre[k].mfY+2*flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
  238. lv.ncolor = xvepre[k].mnlanecolor;
  239. mvectorlanemark.push_back(lv);
  240. }
  241. if((nmarktype == 2)||(nmarktype == 4)||(IsDrawMark(xvepre[k].mS)))
  242. {
  243. lv.mPoints[0].setX(xvepre[k].mfX + flmw * cos(xvenxt[k].mfhdg - M_PI/2.0));
  244. lv.mPoints[0].setY((xvepre[k].mfY+flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
  245. lv.mPoints[1].setX(xvenxt[k].mfX+ flmw * cos(xvepre[k].mfhdg - M_PI/2.0));
  246. lv.mPoints[1].setY((xvenxt[k].mfY+flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
  247. lv.mPoints[2].setX(xvenxt[k].mfX + 2*flmw * cos(xvenxt[k].mfhdg - M_PI/2.0));
  248. lv.mPoints[2].setY((xvenxt[k].mfY+2*flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
  249. lv.mPoints[3].setX(xvepre[k].mfX+ 2*flmw * cos(xvepre[k].mfhdg - M_PI/2.0));
  250. lv.mPoints[3].setY((xvepre[k].mfY+2*flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
  251. lv.ncolor = xvepre[k].mnlanecolor;
  252. mvectorlanemark.push_back(lv);
  253. }
  254. }
  255. }
  256. // }
  257. }
  258. }
  259. }
  260. return;
  261. // qDebug("size is %d ",nsize);
  262. for(i=0;i<nsize;i++)
  263. {
  264. // qDebug("i = %d",i);
  265. double fdis = sqrt(pow(mvectorline[i].mendx - mvectorline[i].mstartx,2)+pow(mvectorline[i].mendy - mvectorline[i].mstarty,2));
  266. if(fdis == 0)continue;
  267. std::vector<iv::LanePoint> xvectorlp1 = xodrfunc::GetAllLanePoint(mpRoad,mvectorline[i].mE - fdis,
  268. mvectorline[i].mstartx,mvectorline[i].mstarty *(-1),mvectorline[i].mfHdg);
  269. std::vector<iv::LanePoint> xvectorlp2 = xodrfunc::GetAllLanePoint(mpRoad,mvectorline[i].mE,
  270. mvectorline[i].mendx,mvectorline[i].mendy *(-1),mvectorline[i].mfHdg);
  271. if(xvectorlp1.size() == xvectorlp2.size())
  272. {
  273. for(j=0;j<(xvectorlp1.size());j++)
  274. {
  275. iv::laneviewdata lv;
  276. iv::LanePoint lpstart1,lpstart2,lpend1,lpend2;
  277. int nlane1_index_start,nlane2_index_start;
  278. int nlane1_index_end,nlane2_index_end;
  279. nlane1_index_start = j;
  280. lpstart1 = xvectorlp1[nlane1_index_start];
  281. if(lpstart1.mnlane == 0)
  282. {
  283. continue;
  284. }
  285. nlane1_index_end = 1000;
  286. nlane2_index_end = 1000;
  287. if(lpstart1.mnlane>0)nlane2_index_start = j+1;
  288. else nlane2_index_start = j-1;
  289. if((nlane2_index_start < 0)||(nlane2_index_start>= xvectorlp1.size()))
  290. {
  291. std::cout<<"nlane2_index_start error."<<std::endl;
  292. continue;
  293. }
  294. for(int k=0;k<xvectorlp2.size();k++)
  295. {
  296. if(xvectorlp2[k].mnlane == xvectorlp1[nlane1_index_start].mnlane)
  297. {
  298. nlane1_index_end = k;
  299. }
  300. if(xvectorlp2[k].mnlane == xvectorlp1[nlane2_index_start].mnlane)
  301. {
  302. nlane2_index_end = k;
  303. }
  304. if((nlane1_index_end != 1000)&&(nlane2_index_end != 1000))
  305. {
  306. break;
  307. }
  308. }
  309. if((nlane1_index_end == 1000)||(nlane2_index_end == 1000))
  310. {
  311. continue;
  312. }
  313. lpstart1 = xvectorlp1[nlane1_index_start];
  314. lpstart2 = xvectorlp1[nlane2_index_start];
  315. lpend1 = xvectorlp2[nlane1_index_end];
  316. lpend2 = xvectorlp2[nlane2_index_end];
  317. lv.mPoints[0].setX(lpstart1.mfX);
  318. lv.mPoints[0].setY(lpstart1.mfY*(-1));
  319. lv.mPoints[1].setX(lpstart2.mfX);
  320. lv.mPoints[1].setY(lpstart2.mfY*(-1));
  321. lv.mPoints[2].setX(lpend2.mfX);
  322. lv.mPoints[2].setY(lpend2.mfY*(-1));
  323. lv.mPoints[3].setX(lpend1.mfX);
  324. lv.mPoints[3].setY(lpend1.mfY*(-1));
  325. mvectorlaneview.push_back(lv);
  326. // qDebug("push size is %d ",mvectorlaneview.size());
  327. }
  328. }
  329. }
  330. }
  331. void roadviewitem::CalcLine()
  332. {
  333. // Road * pRoad = mpRoad;
  334. mvectorline.clear();
  335. if(mbShowLane)
  336. {
  337. mvectorlaneline.clear();
  338. }
  339. int j;
  340. double S = 0;
  341. int nlanesec = 0;
  342. double lanesection_s = 0;
  343. double lane_s = 0;
  344. if(mpRoad->GetLaneSectionCount()<1)
  345. {
  346. qDebug("no lane,return;");
  347. return;
  348. }
  349. LaneSection * pLS = mpRoad->GetLaneSection(0);
  350. lanesection_s = pLS->GetS();
  351. iv::lanesectionlinese xlsl;
  352. int nLastSection;
  353. if(mbShowLane)
  354. {
  355. if(mpRoad->GetGeometryBlockCount() > 0)
  356. {
  357. double fx = mpRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetX();
  358. double fy = mpRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetY();
  359. double fhdg = mpRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetHdg();
  360. std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,0,fx,fy,fhdg);
  361. iv::lanesectionpoint xvecsp;
  362. xvecsp.mvectorlanepoint = xveclp;
  363. xlsl.mnsec = 0;
  364. nLastSection = 0;
  365. xlsl.mvectorlanelinese.push_back(xvecsp);
  366. }
  367. }
  368. for(j=0;j<mpRoad->GetGeometryBlockCount();j++)
  369. {
  370. if(nlanesec < (mpRoad->GetLaneSectionCount() -1))
  371. {
  372. if(mpRoad->GetLaneSection(nlanesec+1)->GetS() <= S)
  373. {
  374. nlanesec++;
  375. pLS = mpRoad->GetLaneSection(nlanesec);
  376. lanesection_s = pLS->GetS();
  377. lane_s = 0;
  378. }
  379. }
  380. GeometryBlock * pgeob = mpRoad->GetGeometryBlock(j);
  381. double x,y;
  382. double x_center,y_center;
  383. double R;
  384. RoadGeometry * pg;
  385. GeometryArc * parc;
  386. GeometryParamPoly3 * ppp3;
  387. GeometrySpiral *pSpiral;
  388. double rel_x,rel_y,rel_hdg;
  389. pg = pgeob->GetGeometryAt(0);
  390. x = pg->GetX();
  391. y = pg->GetY();
  392. iv::lineviewdata xline;
  393. switch (pg->GetGeomType()) {
  394. case 0:
  395. {
  396. xline.mstartx = x;
  397. xline.mstarty = y *(-1.0);
  398. int ncount = pg->GetLength() * 10.0/mfratio;
  399. double fstep;
  400. if(ncount > 0)fstep = pg->GetLength()/ncount;
  401. int i;
  402. for(i=1;i<ncount;i++)
  403. {
  404. double xtem,ytem;
  405. xtem = x + (i*fstep)*cos(pg->GetHdg());
  406. ytem = y + (i*fstep)*sin(pg->GetHdg());
  407. xline.mendx = xtem;
  408. xline.mendy = ytem*(-1.0);
  409. xline.mE = xline.mE + fstep;
  410. xline.mfHdg = pg->GetHdg();
  411. CalcPoints(&xline);
  412. mvectorline.push_back(xline);
  413. if(mbShowLane)
  414. {
  415. std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
  416. if(xveclp.size() > 0)
  417. {
  418. if(xveclp[0].mnLaneSection != nLastSection)
  419. {
  420. mvectorlaneline.push_back(xlsl);
  421. iv::lanesectionpoint xvecsp;
  422. xvecsp.mvectorlanepoint = xveclp;
  423. xlsl.mnsec = xveclp[0].mnLaneSection;
  424. nLastSection =xlsl.mnsec;
  425. xlsl.mvectorlanelinese.push_back(xvecsp);
  426. }
  427. else
  428. {
  429. if(xlsl.mvectorlanelinese.size() > 0)
  430. {
  431. if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
  432. {
  433. iv::lanesectionpoint xvecsp;
  434. xvecsp.mvectorlanepoint = xveclp;
  435. xlsl.mnsec = xveclp[0].mnLaneSection;
  436. nLastSection =xlsl.mnsec;
  437. xlsl.mvectorlanelinese.push_back(xvecsp);
  438. }
  439. else
  440. {
  441. mvectorlaneline.push_back(xlsl);
  442. iv::lanesectionpoint xvecsp;
  443. xvecsp.mvectorlanepoint = xveclp;
  444. xlsl.mnsec = xveclp[0].mnLaneSection;
  445. nLastSection =xlsl.mnsec;
  446. xlsl.mvectorlanelinese.push_back(xvecsp);
  447. }
  448. }
  449. }
  450. }
  451. }
  452. xline.mstartx = xtem;
  453. xline.mstarty = ytem*(-1.0);
  454. }
  455. if(ncount > 1)xline.mE = xline.mE + (pg->GetLength() -(ncount -1)*fstep);
  456. else xline.mE = xline.mE + pg->GetLength();
  457. xline.mendx = x + pg->GetLength() * cos(pg->GetHdg());
  458. xline.mendy = (y + pg->GetLength() * sin(pg->GetHdg()))*(-1.0);
  459. // painter->drawLine(QPoint(x*mnfac,y*mnfac*(-1)),
  460. // QPoint((x + pg->GetLength() * cos(pg->GetHdg()))*mnfac,(y + pg->GetLength() * sin(pg->GetHdg()))*mnfac*(-1)));
  461. CalcPoints(&xline);
  462. mvectorline.push_back(xline);
  463. }
  464. break;
  465. case 1:
  466. pSpiral = (GeometrySpiral * )pg;
  467. {
  468. int ncount = pSpiral->GetLength() * mfratio;
  469. if(ncount < 2)ncount = 2;
  470. double sstep = pSpiral->GetLength()/((double)ncount);
  471. int k;
  472. double x0,y0,hdg0,s0;
  473. x0 = pSpiral->GetX();
  474. y0 = pSpiral->GetY();
  475. s0 = pSpiral->GetS();
  476. hdg0 = pSpiral->GetHdg() ;
  477. pSpiral->GetCoords(s0,rel_x,rel_y,rel_hdg);
  478. x = rel_x;
  479. y = rel_y;
  480. xline.mstartx = x;
  481. xline.mstarty = y *(-1.0);
  482. for(k=1;k<=ncount;k++)
  483. {
  484. pSpiral->GetCoords(s0+sstep*k,rel_x,rel_y,rel_hdg);
  485. x = rel_x;
  486. y = rel_y;
  487. xline.mendx = x;
  488. xline.mendy = y*(-1.0);
  489. xline.mE = xline.mE + sstep *k;
  490. xline.mfHdg = xodrfunc::CalcHdg(QPointF(xline.mstartx,xline.mstarty*(-1)),QPointF(xline.mendx,xline.mendy*(-1)));
  491. CalcPoints(&xline);
  492. mvectorline.push_back(xline);
  493. if(mbShowLane)
  494. {
  495. std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
  496. if(xveclp.size() > 0)
  497. {
  498. if(xveclp[0].mnLaneSection != nLastSection)
  499. {
  500. mvectorlaneline.push_back(xlsl);
  501. iv::lanesectionpoint xvecsp;
  502. xvecsp.mvectorlanepoint = xveclp;
  503. xlsl.mnsec = xveclp[0].mnLaneSection;
  504. nLastSection =xlsl.mnsec;
  505. xlsl.mvectorlanelinese.push_back(xvecsp);
  506. }
  507. else
  508. {
  509. if(xlsl.mvectorlanelinese.size() > 0)
  510. {
  511. if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
  512. {
  513. iv::lanesectionpoint xvecsp;
  514. xvecsp.mvectorlanepoint = xveclp;
  515. xlsl.mnsec = xveclp[0].mnLaneSection;
  516. nLastSection =xlsl.mnsec;
  517. xlsl.mvectorlanelinese.push_back(xvecsp);
  518. }
  519. else
  520. {
  521. mvectorlaneline.push_back(xlsl);
  522. iv::lanesectionpoint xvecsp;
  523. xvecsp.mvectorlanepoint = xveclp;
  524. xlsl.mnsec = xveclp[0].mnLaneSection;
  525. nLastSection =xlsl.mnsec;
  526. xlsl.mvectorlanelinese.push_back(xvecsp);
  527. }
  528. }
  529. }
  530. }
  531. }
  532. xline.mstartx = x;
  533. xline.mstarty = y*(-1.0);
  534. }
  535. }
  536. // qDebug("spi");
  537. break;
  538. case 2:
  539. {
  540. parc = (GeometryArc *)pg;
  541. R = abs(1.0/parc->GetCurvature());
  542. if(parc->GetCurvature() > 0)
  543. {
  544. x_center = pg->GetX() + R *cos(pg->GetHdg() + M_PI/2.0);
  545. y_center = pg->GetY() + R * sin(pg->GetHdg() + M_PI/2.0);
  546. }
  547. else
  548. {
  549. x_center = pg->GetX() + R *cos(pg->GetHdg() -M_PI/2.0);
  550. y_center = pg->GetY() + R * sin(pg->GetHdg() - M_PI/2.0);
  551. }
  552. int k;
  553. int ncount = parc->GetLength() * 3.0/mfratio;
  554. if(ncount< 2)ncount = 2;
  555. double curv = parc->GetCurvature();
  556. double hdgstep;
  557. double hdg0 = parc->GetHdg();
  558. double hdgnow = parc->GetHdg();
  559. if(ncount > 0) hdgstep= (parc->GetLength()/R)/ncount;
  560. double x_draw,y_draw;
  561. if(curv > 0)
  562. {
  563. hdgnow = hdg0 ;
  564. x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
  565. y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
  566. }
  567. else
  568. {
  569. hdgnow = hdg0;
  570. x_draw = x_center + R *cos(hdgnow + M_PI/2.0);
  571. y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
  572. }
  573. xline.mstartx = x_draw;
  574. xline.mstarty = y_draw *(-1.0);
  575. for(k=1;k<=ncount;k++)
  576. {
  577. if(curv > 0)
  578. {
  579. hdgnow = hdg0 + k*hdgstep;
  580. x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
  581. y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
  582. }
  583. else
  584. {
  585. hdgnow = hdg0 - k * hdgstep;
  586. x_draw = x_center + R *cos(hdgnow + M_PI/2.0);
  587. y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
  588. }
  589. xline.mendx = x_draw;
  590. xline.mendy = y_draw*(-1.0);
  591. xline.mE = xline.mE + hdgstep * R;
  592. CalcPoints(&xline);
  593. xline.mfHdg = xodrfunc::CalcHdg(QPointF(xline.mstartx,xline.mstarty*(-1)),QPointF(xline.mendx,xline.mendy*(-1)));
  594. mvectorline.push_back(xline);
  595. if(mbShowLane)
  596. {
  597. std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
  598. if(xveclp.size() > 0)
  599. {
  600. if(xveclp[0].mnLaneSection != nLastSection)
  601. {
  602. mvectorlaneline.push_back(xlsl);
  603. iv::lanesectionpoint xvecsp;
  604. xvecsp.mvectorlanepoint = xveclp;
  605. xlsl.mnsec = xveclp[0].mnLaneSection;
  606. nLastSection =xlsl.mnsec;
  607. xlsl.mvectorlanelinese.push_back(xvecsp);
  608. }
  609. else
  610. {
  611. if(xlsl.mvectorlanelinese.size() > 0)
  612. {
  613. if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
  614. {
  615. iv::lanesectionpoint xvecsp;
  616. xvecsp.mvectorlanepoint = xveclp;
  617. xlsl.mnsec = xveclp[0].mnLaneSection;
  618. nLastSection =xlsl.mnsec;
  619. xlsl.mvectorlanelinese.push_back(xvecsp);
  620. }
  621. else
  622. {
  623. mvectorlaneline.push_back(xlsl);
  624. iv::lanesectionpoint xvecsp;
  625. xvecsp.mvectorlanepoint = xveclp;
  626. xlsl.mnsec = xveclp[0].mnLaneSection;
  627. nLastSection =xlsl.mnsec;
  628. xlsl.mvectorlanelinese.push_back(xvecsp);
  629. }
  630. }
  631. }
  632. }
  633. }
  634. xline.mstartx = x_draw;
  635. xline.mstarty = y_draw*(-1.0);
  636. }
  637. }
  638. break;
  639. case 4:
  640. {
  641. ppp3 = (GeometryParamPoly3 * )pg;
  642. int ncount = ppp3->GetLength()* 3.0/ mfratio;
  643. if(ncount < 2)ncount = 2;
  644. double sstep;
  645. if(ncount > 0)sstep = ppp3->GetLength()/ncount;
  646. else sstep = 10000.0;
  647. double s = 0;
  648. double xtem,ytem;
  649. xtem = ppp3->GetuA() + ppp3->GetuB() * s + ppp3->GetuC() * s*s + ppp3->GetuD() * s*s*s;
  650. ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
  651. x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
  652. y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
  653. s = s+ sstep;
  654. xline.mstartx = x;
  655. xline.mstarty = y *(-1.0);
  656. while(s <= ppp3->GetLength())
  657. {
  658. xtem = ppp3->GetuA() + ppp3->GetuB() * s + ppp3->GetuC() * s*s + ppp3->GetuD() * s*s*s;
  659. ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
  660. x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
  661. y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
  662. xline.mendx = x;
  663. xline.mendy = y*(-1.0);
  664. xline.mE = xline.mE + sstep;
  665. CalcPoints(&xline);
  666. xline.mfHdg = xodrfunc::CalcHdg(QPointF(xline.mstartx,xline.mstarty*(-1)),QPointF(xline.mendx,xline.mendy*(-1)));
  667. mvectorline.push_back(xline);
  668. if(mbShowLane)
  669. {
  670. std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
  671. if(xveclp.size() > 0)
  672. {
  673. if(xveclp[0].mnLaneSection != nLastSection)
  674. {
  675. mvectorlaneline.push_back(xlsl);
  676. iv::lanesectionpoint xvecsp;
  677. xvecsp.mvectorlanepoint = xveclp;
  678. xlsl.mnsec = xveclp[0].mnLaneSection;
  679. nLastSection =xlsl.mnsec;
  680. xlsl.mvectorlanelinese.push_back(xvecsp);
  681. }
  682. else
  683. {
  684. if(xlsl.mvectorlanelinese.size() > 0)
  685. {
  686. if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
  687. {
  688. iv::lanesectionpoint xvecsp;
  689. xvecsp.mvectorlanepoint = xveclp;
  690. xlsl.mnsec = xveclp[0].mnLaneSection;
  691. nLastSection =xlsl.mnsec;
  692. xlsl.mvectorlanelinese.push_back(xvecsp);
  693. }
  694. else
  695. {
  696. mvectorlaneline.push_back(xlsl);
  697. iv::lanesectionpoint xvecsp;
  698. xvecsp.mvectorlanepoint = xveclp;
  699. xlsl.mnsec = xveclp[0].mnLaneSection;
  700. nLastSection =xlsl.mnsec;
  701. xlsl.mvectorlanelinese.push_back(xvecsp);
  702. }
  703. }
  704. }
  705. }
  706. }
  707. xline.mstartx = x;
  708. xline.mstarty = y*(-1.0);
  709. s = s+ sstep;
  710. }
  711. }
  712. break;
  713. default:
  714. break;
  715. }
  716. // painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
  717. }
  718. mvectorlaneline.push_back(xlsl);
  719. CalcMaxMin();
  720. mbNeedCalc = false;
  721. mfoldcalratio = mfratio;
  722. return;
  723. if(mvectorline.size()<0)return;
  724. if(mvectorline.size() <= 2)
  725. {
  726. mtextx = (mvectorline[0].mstartx + mvectorline[0].mendx)/2.0;
  727. mtexty = (mvectorline[0].mstarty + mvectorline[0].mendy)/2.0;
  728. }
  729. else
  730. {
  731. int i;
  732. mtextx = mvectorline[0].mendx;
  733. mtexty = mvectorline[0].mendy;
  734. for(i=0;i<mvectorline.size();i++)
  735. {
  736. qDebug("run i is %d size is %d ",i,mvectorline.size());
  737. if(mvectorline[i].mE >= (mpRoad->GetRoadLength()/2.0))
  738. {
  739. mtextx = mvectorline[i].mendx;
  740. mtexty = mvectorline[i].mendy;
  741. break;
  742. }
  743. }
  744. }
  745. }
  746. void roadviewitem::setratio(float ratio)
  747. {
  748. mfratio = ratio;
  749. }
  750. void roadviewitem::CalcPoints(iv::lineviewdata *plinedata)
  751. {
  752. float fwidth = mfwidth * mfratio;
  753. double fhdg = geofit::CalcHdg(plinedata->mstartx,plinedata->mstarty,plinedata->mendx,plinedata->mendy);
  754. plinedata->mPoints[0].setX(plinedata->mstartx + fwidth * cos(fhdg -M_PI/2.0)/2.0 );
  755. plinedata->mPoints[0].setY((plinedata->mstarty + fwidth * sin(fhdg -M_PI/2.0)/2.0 )*(1.0));
  756. plinedata->mPoints[1].setX(plinedata->mendx + fwidth * cos(fhdg -M_PI/2.0)/2.0 );
  757. plinedata->mPoints[1].setY((plinedata->mendy + fwidth * sin(fhdg -M_PI/2.0)/2.0 )*(1.0));
  758. plinedata->mPoints[2].setX(plinedata->mendx + fwidth * cos(fhdg +M_PI/2.0)/2.0 );
  759. plinedata->mPoints[2].setY((plinedata->mendy + fwidth * sin(fhdg +M_PI/2.0)/2.0 )*(1.0));
  760. plinedata->mPoints[3].setX(plinedata->mstartx + fwidth * cos(fhdg +M_PI/2.0)/2.0 );
  761. plinedata->mPoints[3].setY((plinedata->mstarty + fwidth * sin(fhdg +M_PI/2.0)/2.0 )*(1.0));
  762. }
  763. void roadviewitem::CalcMaxMin()
  764. {
  765. if(mvectorline.size()<1)return;
  766. mfxmax = mvectorline[0].mstartx;
  767. mfxmin = mvectorline[0].mstartx;
  768. mfymax = mvectorline[0].mstarty;
  769. mfymin = mvectorline[0].mstarty;
  770. int i;
  771. int nsize = mvectorline.size();
  772. if(nsize < 1)return;
  773. mtextx = mvectorline[0].mendx;
  774. mtexty = mvectorline[0].mendy;
  775. bool bFindTextPos = false;
  776. for(i=0;i<nsize;i++)
  777. {
  778. double x,y;
  779. x = mvectorline[i].mstartx;
  780. y = mvectorline[i].mstarty;
  781. if(mfxmin> x)mfxmin = x;
  782. if(mfymin > y)mfymin = y;
  783. if(mfxmax < x)mfxmax = x;
  784. if(mfymax < y)mfymax = y;
  785. x = mvectorline[i].mendx;
  786. y = mvectorline[i].mendy;
  787. if(mfxmin> x)mfxmin = x;
  788. if(mfymin > y)mfymin = y;
  789. if(mfxmax < x)mfxmax = x;
  790. if(mfymax < y)mfymax = y;
  791. if(bFindTextPos == false)
  792. {
  793. // double xE = mvectorline[i].mE;
  794. if(mvectorline[i].mE >= (mpRoad->GetRoadLength()/2.0))
  795. {
  796. mtextx = mvectorline[i].mendx;
  797. mtexty = mvectorline[i].mendy;
  798. bFindTextPos = true;
  799. }
  800. }
  801. }
  802. }
  803. void roadviewitem::setmark(bool bMark)
  804. {
  805. mbMark = bMark;
  806. }
  807. Road * roadviewitem::GetRoad()
  808. {
  809. return mpRoad;
  810. }
  811. void roadviewitem::setlaneshow(bool bShow)
  812. {
  813. mbShowLane = bShow;
  814. mbNeedCalc = true;
  815. }
  816. void roadviewitem::setroadidshow(bool bShow)
  817. {
  818. mbShowRoadID = bShow;
  819. // mbNeedCalc = true;
  820. }
  821. void roadviewitem::setlineshow(bool bShow)
  822. {
  823. mbShowLine = bShow;
  824. }