|
@@ -0,0 +1,944 @@
|
|
|
+#include "roadviewitem.h"
|
|
|
+
|
|
|
+#include <math.h>
|
|
|
+
|
|
|
+#include "geofit.h"
|
|
|
+
|
|
|
+#include <QtWidgets>
|
|
|
+
|
|
|
+#include <QFont>
|
|
|
+
|
|
|
+roadviewitem::roadviewitem(Road * pRoad)
|
|
|
+{
|
|
|
+ mpRoad = pRoad;
|
|
|
+ mbNeedCalc = true;
|
|
|
+}
|
|
|
+
|
|
|
+QRectF roadviewitem::boundingRect() const
|
|
|
+{
|
|
|
+// qDebug("ratio is %f",mfratio);
|
|
|
+// return QRectF((mfxmin - mfwidth - 15)*mfratio,(mfymin-mfwidth-15)*mfratio,(mfxmax - mfxmin + 2.0*mfwidth+30)*mfratio,
|
|
|
+// (mfymax - mfymin+2.0*mfwidth+30)*mfratio);
|
|
|
+ return QRectF( - 10000,-10000 ,20000,
|
|
|
+ 20000);
|
|
|
+ // return QRectF(-10000,-10000,20000,20000);
|
|
|
+// float fwidth = mfwidth * mfratio;
|
|
|
+// return QRectF(mfxmin - fwidth - 15,mfymin-fwidth-15,mfxmax - mfxmin + 2.0*fwidth+30,
|
|
|
+// mfymax - mfymin+2.0*fwidth+30);
|
|
|
+ return QRectF(mfxmin - 10000,mfymin-10000,mfxmax - mfxmin + 20000,
|
|
|
+ mfymax - mfymin+20000);
|
|
|
+
|
|
|
+
|
|
|
+ // return QRectF(mfxmin - fwidth - 15,mfymin-fwidth-15,mfxmax - mfxmin + 2.0*fwidth+30,mfymax - mfymin+2.0*fwidth+30);
|
|
|
+// return QRectF(-10000,-10000,20000,20000);
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
|
|
+{
|
|
|
+ (void)option;
|
|
|
+
|
|
|
+ int i;
|
|
|
+
|
|
|
+// if((mfratio/mfoldcalratio>3.0)||(mfratio/mfoldcalratio<0.3))
|
|
|
+// {
|
|
|
+// mbNeedCalc = true;
|
|
|
+// }
|
|
|
+
|
|
|
+ if(mfratio != mfoldcalratio)mbNeedCalc = true;
|
|
|
+// qDebug("painter");
|
|
|
+ Q_UNUSED(option);
|
|
|
+ Q_UNUSED(widget);
|
|
|
+
|
|
|
+ if(mbNeedCalc)
|
|
|
+ {
|
|
|
+ CalcLine();
|
|
|
+ CalcLane();
|
|
|
+ }
|
|
|
+
|
|
|
+ painter->setPen(Qt::NoPen);
|
|
|
+// painter->setBrush(Qt::darkGray);
|
|
|
+// painter->drawRect(0,0,mnlen,mnwidth*mfratio);
|
|
|
+
|
|
|
+ if(mbShowLine)
|
|
|
+ {
|
|
|
+ if(mbMark)painter->setBrush(Qt::red);
|
|
|
+ else
|
|
|
+ painter->setBrush(Qt::white);
|
|
|
+
|
|
|
+
|
|
|
+ for(i=0;i<mvectorline.size();i++)
|
|
|
+ {
|
|
|
+ painter->drawPolygon(mvectorline[i].mPoints,4);
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ painter->setBrush(Qt::darkGray);
|
|
|
+ int nsize = mvectorlaneview.size();
|
|
|
+ for(i=0;i<nsize;i++)
|
|
|
+ {
|
|
|
+ switch (mvectorlaneview[i].ntype) {
|
|
|
+ case 2:
|
|
|
+ painter->setBrush(Qt::darkGray);
|
|
|
+ break;
|
|
|
+ case 8:
|
|
|
+ painter->setBrush(Qt::red);
|
|
|
+ break;
|
|
|
+ case 9:
|
|
|
+ painter->setBrush(QColor(0xB2,0xB2,0xD6));
|
|
|
+ break;
|
|
|
+ default:
|
|
|
+ painter->setBrush(Qt::darkGreen);
|
|
|
+ break;
|
|
|
+ }
|
|
|
+ painter->drawPolygon(mvectorlaneview[i].mPoints,4);
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ painter->setBrush(Qt::white);
|
|
|
+
|
|
|
+ int nsize = mvectorlanemark.size();
|
|
|
+ for(i=0;i<nsize;i++)
|
|
|
+ {
|
|
|
+ switch (mvectorlanemark[i].ncolor) {
|
|
|
+ case 0:
|
|
|
+ painter->setBrush(Qt::white);
|
|
|
+ break;
|
|
|
+ case 1:
|
|
|
+ painter->setBrush(Qt::blue);
|
|
|
+ break;
|
|
|
+ case 2:
|
|
|
+ painter->setBrush(Qt::green);
|
|
|
+ break;
|
|
|
+ case 3:
|
|
|
+ painter->setBrush(Qt::red);
|
|
|
+ break;
|
|
|
+ case 4:
|
|
|
+ painter->setBrush(Qt::white);
|
|
|
+ break;
|
|
|
+ case 5:
|
|
|
+ painter->setBrush(Qt::yellow);
|
|
|
+ break;
|
|
|
+ case 6:
|
|
|
+ painter->setBrush(Qt::yellow); //orange use yellow replace
|
|
|
+ break;
|
|
|
+ default:
|
|
|
+ painter->setBrush(Qt::white);
|
|
|
+ break;
|
|
|
+ }
|
|
|
+ painter->drawPolygon(mvectorlanemark[i].mPoints,4);
|
|
|
+ painter->setBrush(Qt::white);
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+ QPen pen;
|
|
|
+ pen.setWidth(1);
|
|
|
+ pen.setColor(Qt::white);
|
|
|
+ painter->setPen(pen);
|
|
|
+
|
|
|
+ QFont font = painter->font();
|
|
|
+ font.setPixelSize(3);
|
|
|
+ painter->setFont(font);
|
|
|
+
|
|
|
+ if(mbShowRoadID)
|
|
|
+ {
|
|
|
+ painter->drawText(mtextx,mtexty,mpRoad->GetRoadId().data());
|
|
|
+ }
|
|
|
+
|
|
|
+ painter->setBrush(Qt::NoBrush);
|
|
|
+ if(mbShowLine)
|
|
|
+ {
|
|
|
+ if(mbMark)
|
|
|
+ {
|
|
|
+ if(mvectorline.size()>0)
|
|
|
+ {
|
|
|
+ painter->drawEllipse(mvectorline[0].mstartx-1.5,mvectorline[0].mstarty-1.5,3,3);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+// QPen pen;
|
|
|
+// pen.setWidth(1);
|
|
|
+// pen.setColor(Qt::white);
|
|
|
+// painter->setPen(pen);
|
|
|
+// for(i=0;i<mvectorline.size();i++)
|
|
|
+// {
|
|
|
+// painter->drawLine(mvectorline[i].mstartx,mvectorline[i].mstarty,
|
|
|
+// mvectorline[i].mendx,mvectorline[i].mendy);
|
|
|
+// }
|
|
|
+ // painter->drawLine(1,0,mnlen-1,0);
|
|
|
+
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+bool roadviewitem::IsDrawMark(double s)
|
|
|
+{
|
|
|
+ const double dotdis = 10.0;
|
|
|
+ const double dotlen = 5.0;
|
|
|
+
|
|
|
+ double y = fmod(s,dotdis);
|
|
|
+ if(y>dotlen)return true;
|
|
|
+ else
|
|
|
+ {
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::CalcLane()
|
|
|
+{
|
|
|
+ if(mbShowLane == false)return;
|
|
|
+ int i,j;
|
|
|
+ int nsize = mvectorline.size();
|
|
|
+ mvectorlaneview.clear();
|
|
|
+ mvectorlanemark.clear();
|
|
|
+
|
|
|
+ double flmw = 0.15;
|
|
|
+
|
|
|
+
|
|
|
+ for(i=0;i<mvectorlaneline.size();i++)
|
|
|
+ {
|
|
|
+ for(j=0;j<(mvectorlaneline[i].mvectorlanelinese.size()-1);j++)
|
|
|
+ {
|
|
|
+ std::vector<iv::LanePoint> xvepre = mvectorlaneline[i].mvectorlanelinese[j].mvectorlanepoint;
|
|
|
+ std::vector<iv::LanePoint> xvenxt = mvectorlaneline[i].mvectorlanelinese[j+1].mvectorlanepoint;
|
|
|
+ if((xvepre.size()<2)||(xvenxt.size()<2)||(xvenxt.size() != xvepre.size()))
|
|
|
+ {
|
|
|
+ continue;
|
|
|
+ }
|
|
|
+ int k;
|
|
|
+ for(k=0;k<(xvepre.size()-1);k++)
|
|
|
+ {
|
|
|
+
|
|
|
+ iv::laneviewdata lv;
|
|
|
+ lv.mPoints[0].setX(xvepre[k].mfX);
|
|
|
+ lv.mPoints[0].setY(xvepre[k].mfY*(-1.0));
|
|
|
+ lv.mPoints[1].setX(xvenxt[k].mfX);
|
|
|
+ lv.mPoints[1].setY(xvenxt[k].mfY*(-1.0));
|
|
|
+ lv.mPoints[2].setX(xvenxt[k+1].mfX);
|
|
|
+ lv.mPoints[2].setY(xvenxt[k+1].mfY*(-1.0));
|
|
|
+ lv.mPoints[3].setX(xvepre[k+1].mfX);
|
|
|
+ lv.mPoints[3].setY(xvepre[k+1].mfY*(-1.0));
|
|
|
+ if(xvepre[k].mnlane>0)lv.ntype = xvepre[k].mnlanetype;
|
|
|
+ else lv.ntype = xvepre[k+1].mnlanetype;
|
|
|
+ mvectorlaneview.push_back(lv);
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ for(i=0;i<mvectorlaneline.size();i++)
|
|
|
+ {
|
|
|
+ for(j=0;j<(mvectorlaneline[i].mvectorlanelinese.size()-1);j++)
|
|
|
+ {
|
|
|
+ std::vector<iv::LanePoint> xvepre = mvectorlaneline[i].mvectorlanelinese[j].mvectorlanepoint;
|
|
|
+ std::vector<iv::LanePoint> xvenxt = mvectorlaneline[i].mvectorlanelinese[j+1].mvectorlanepoint;
|
|
|
+ if((xvepre.size()<2)||(xvenxt.size()<2)||(xvenxt.size() != xvepre.size()))
|
|
|
+ {
|
|
|
+ continue;
|
|
|
+ }
|
|
|
+ int k;
|
|
|
+ for(k=0;k<(xvepre.size());k++)
|
|
|
+ {
|
|
|
+ iv::lanemark lv;
|
|
|
+ int nmarktype = xvepre[k].mnlanemarktype;
|
|
|
+ if(nmarktype >= 0)
|
|
|
+ {
|
|
|
+ if(nmarktype<2)
|
|
|
+ {
|
|
|
+ if((nmarktype == 0)||(IsDrawMark(xvepre[k].mS)))
|
|
|
+ {
|
|
|
+ lv.mPoints[0].setX(xvepre[k].mfX + 0.5*flmw * cos(xvenxt[k].mfhdg - M_PI/2.0));
|
|
|
+ lv.mPoints[0].setY((xvepre[k].mfY+0.5*flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
|
|
|
+ lv.mPoints[1].setX(xvenxt[k].mfX+ 0.5*flmw * cos(xvepre[k].mfhdg - M_PI/2.0));
|
|
|
+ lv.mPoints[1].setY((xvenxt[k].mfY+0.5*flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
|
|
|
+
|
|
|
+ lv.mPoints[2].setX(xvenxt[k].mfX + 0.5*flmw * cos(xvenxt[k].mfhdg + M_PI/2.0));
|
|
|
+ lv.mPoints[2].setY((xvenxt[k].mfY+0.5*flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
|
|
|
+ lv.mPoints[3].setX(xvepre[k].mfX+ 0.5*flmw * cos(xvepre[k].mfhdg + M_PI/2.0));
|
|
|
+ lv.mPoints[3].setY((xvepre[k].mfY+0.5*flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
|
|
|
+ lv.ncolor = xvepre[k].mnlanecolor;
|
|
|
+ mvectorlanemark.push_back(lv);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ if((nmarktype == 2)||(nmarktype == 3)||(IsDrawMark(xvepre[k].mS)))
|
|
|
+ {
|
|
|
+ lv.mPoints[0].setX(xvepre[k].mfX + flmw * cos(xvenxt[k].mfhdg + M_PI/2.0));
|
|
|
+ lv.mPoints[0].setY((xvepre[k].mfY+flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
|
|
|
+ lv.mPoints[1].setX(xvenxt[k].mfX+ flmw * cos(xvepre[k].mfhdg + M_PI/2.0));
|
|
|
+ lv.mPoints[1].setY((xvenxt[k].mfY+flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
|
|
|
+
|
|
|
+ lv.mPoints[2].setX(xvenxt[k].mfX + 2*flmw * cos(xvenxt[k].mfhdg + M_PI/2.0));
|
|
|
+ lv.mPoints[2].setY((xvenxt[k].mfY+2*flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
|
|
|
+ lv.mPoints[3].setX(xvepre[k].mfX+ 2*flmw * cos(xvepre[k].mfhdg + M_PI/2.0));
|
|
|
+ lv.mPoints[3].setY((xvepre[k].mfY+2*flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
|
|
|
+ lv.ncolor = xvepre[k].mnlanecolor;
|
|
|
+ mvectorlanemark.push_back(lv);
|
|
|
+ }
|
|
|
+ if((nmarktype == 2)||(nmarktype == 4)||(IsDrawMark(xvepre[k].mS)))
|
|
|
+ {
|
|
|
+ lv.mPoints[0].setX(xvepre[k].mfX + flmw * cos(xvenxt[k].mfhdg - M_PI/2.0));
|
|
|
+ lv.mPoints[0].setY((xvepre[k].mfY+flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
|
|
|
+ lv.mPoints[1].setX(xvenxt[k].mfX+ flmw * cos(xvepre[k].mfhdg - M_PI/2.0));
|
|
|
+ lv.mPoints[1].setY((xvenxt[k].mfY+flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
|
|
|
+
|
|
|
+ lv.mPoints[2].setX(xvenxt[k].mfX + 2*flmw * cos(xvenxt[k].mfhdg - M_PI/2.0));
|
|
|
+ lv.mPoints[2].setY((xvenxt[k].mfY+2*flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
|
|
|
+ lv.mPoints[3].setX(xvepre[k].mfX+ 2*flmw * cos(xvepre[k].mfhdg - M_PI/2.0));
|
|
|
+ lv.mPoints[3].setY((xvepre[k].mfY+2*flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
|
|
|
+ lv.ncolor = xvepre[k].mnlanecolor;
|
|
|
+
|
|
|
+ mvectorlanemark.push_back(lv);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+ // }
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ return;
|
|
|
+
|
|
|
+// qDebug("size is %d ",nsize);
|
|
|
+ for(i=0;i<nsize;i++)
|
|
|
+ {
|
|
|
+// qDebug("i = %d",i);
|
|
|
+ double fdis = sqrt(pow(mvectorline[i].mendx - mvectorline[i].mstartx,2)+pow(mvectorline[i].mendy - mvectorline[i].mstarty,2));
|
|
|
+ if(fdis == 0)continue;
|
|
|
+ std::vector<iv::LanePoint> xvectorlp1 = xodrfunc::GetAllLanePoint(mpRoad,mvectorline[i].mE - fdis,
|
|
|
+ mvectorline[i].mstartx,mvectorline[i].mstarty *(-1),mvectorline[i].mfHdg);
|
|
|
+ std::vector<iv::LanePoint> xvectorlp2 = xodrfunc::GetAllLanePoint(mpRoad,mvectorline[i].mE,
|
|
|
+ mvectorline[i].mendx,mvectorline[i].mendy *(-1),mvectorline[i].mfHdg);
|
|
|
+
|
|
|
+
|
|
|
+ if(xvectorlp1.size() == xvectorlp2.size())
|
|
|
+ {
|
|
|
+ for(j=0;j<(xvectorlp1.size());j++)
|
|
|
+ {
|
|
|
+ iv::laneviewdata lv;
|
|
|
+ iv::LanePoint lpstart1,lpstart2,lpend1,lpend2;
|
|
|
+ int nlane1_index_start,nlane2_index_start;
|
|
|
+ int nlane1_index_end,nlane2_index_end;
|
|
|
+ nlane1_index_start = j;
|
|
|
+ lpstart1 = xvectorlp1[nlane1_index_start];
|
|
|
+ if(lpstart1.mnlane == 0)
|
|
|
+ {
|
|
|
+ continue;
|
|
|
+ }
|
|
|
+ nlane1_index_end = 1000;
|
|
|
+ nlane2_index_end = 1000;
|
|
|
+
|
|
|
+ if(lpstart1.mnlane>0)nlane2_index_start = j+1;
|
|
|
+ else nlane2_index_start = j-1;
|
|
|
+ if((nlane2_index_start < 0)||(nlane2_index_start>= xvectorlp1.size()))
|
|
|
+ {
|
|
|
+ std::cout<<"nlane2_index_start error."<<std::endl;
|
|
|
+ continue;
|
|
|
+ }
|
|
|
+
|
|
|
+ for(int k=0;k<xvectorlp2.size();k++)
|
|
|
+ {
|
|
|
+ if(xvectorlp2[k].mnlane == xvectorlp1[nlane1_index_start].mnlane)
|
|
|
+ {
|
|
|
+ nlane1_index_end = k;
|
|
|
+ }
|
|
|
+ if(xvectorlp2[k].mnlane == xvectorlp1[nlane2_index_start].mnlane)
|
|
|
+ {
|
|
|
+ nlane2_index_end = k;
|
|
|
+ }
|
|
|
+ if((nlane1_index_end != 1000)&&(nlane2_index_end != 1000))
|
|
|
+ {
|
|
|
+ break;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ if((nlane1_index_end == 1000)||(nlane2_index_end == 1000))
|
|
|
+ {
|
|
|
+ continue;
|
|
|
+ }
|
|
|
+
|
|
|
+ lpstart1 = xvectorlp1[nlane1_index_start];
|
|
|
+ lpstart2 = xvectorlp1[nlane2_index_start];
|
|
|
+ lpend1 = xvectorlp2[nlane1_index_end];
|
|
|
+ lpend2 = xvectorlp2[nlane2_index_end];
|
|
|
+
|
|
|
+
|
|
|
+ lv.mPoints[0].setX(lpstart1.mfX);
|
|
|
+ lv.mPoints[0].setY(lpstart1.mfY*(-1));
|
|
|
+ lv.mPoints[1].setX(lpstart2.mfX);
|
|
|
+ lv.mPoints[1].setY(lpstart2.mfY*(-1));
|
|
|
+ lv.mPoints[2].setX(lpend2.mfX);
|
|
|
+ lv.mPoints[2].setY(lpend2.mfY*(-1));
|
|
|
+ lv.mPoints[3].setX(lpend1.mfX);
|
|
|
+ lv.mPoints[3].setY(lpend1.mfY*(-1));
|
|
|
+ mvectorlaneview.push_back(lv);
|
|
|
+ // qDebug("push size is %d ",mvectorlaneview.size());
|
|
|
+
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+void roadviewitem::CalcLine()
|
|
|
+{
|
|
|
+
|
|
|
+// Road * pRoad = mpRoad;
|
|
|
+ mvectorline.clear();
|
|
|
+
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ mvectorlaneline.clear();
|
|
|
+ }
|
|
|
+ int j;
|
|
|
+ double S = 0;
|
|
|
+ int nlanesec = 0;
|
|
|
+ double lanesection_s = 0;
|
|
|
+ double lane_s = 0;
|
|
|
+ if(mpRoad->GetLaneSectionCount()<1)
|
|
|
+ {
|
|
|
+ qDebug("no lane,return;");
|
|
|
+ return;
|
|
|
+ }
|
|
|
+ LaneSection * pLS = mpRoad->GetLaneSection(0);
|
|
|
+ lanesection_s = pLS->GetS();
|
|
|
+
|
|
|
+ iv::lanesectionlinese xlsl;
|
|
|
+ int nLastSection;
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ if(mpRoad->GetGeometryBlockCount() > 0)
|
|
|
+ {
|
|
|
+
|
|
|
+ double fx = mpRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetX();
|
|
|
+ double fy = mpRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetY();
|
|
|
+ double fhdg = mpRoad->GetGeometryBlock(0)->GetGeometryAt(0)->GetHdg();
|
|
|
+ std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,0,fx,fy,fhdg);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = 0;
|
|
|
+ nLastSection = 0;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ for(j=0;j<mpRoad->GetGeometryBlockCount();j++)
|
|
|
+ {
|
|
|
+ if(nlanesec < (mpRoad->GetLaneSectionCount() -1))
|
|
|
+ {
|
|
|
+ if(mpRoad->GetLaneSection(nlanesec+1)->GetS() <= S)
|
|
|
+ {
|
|
|
+ nlanesec++;
|
|
|
+ pLS = mpRoad->GetLaneSection(nlanesec);
|
|
|
+ lanesection_s = pLS->GetS();
|
|
|
+ lane_s = 0;
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ GeometryBlock * pgeob = mpRoad->GetGeometryBlock(j);
|
|
|
+ double x,y;
|
|
|
+ double x_center,y_center;
|
|
|
+ double R;
|
|
|
+ RoadGeometry * pg;
|
|
|
+ GeometryArc * parc;
|
|
|
+ GeometryParamPoly3 * ppp3;
|
|
|
+ GeometrySpiral *pSpiral;
|
|
|
+ double rel_x,rel_y,rel_hdg;
|
|
|
+ pg = pgeob->GetGeometryAt(0);
|
|
|
+
|
|
|
+ x = pg->GetX();
|
|
|
+ y = pg->GetY();
|
|
|
+ iv::lineviewdata xline;
|
|
|
+
|
|
|
+
|
|
|
+ switch (pg->GetGeomType()) {
|
|
|
+ case 0:
|
|
|
+ {
|
|
|
+ xline.mstartx = x;
|
|
|
+ xline.mstarty = y *(-1.0);
|
|
|
+ int ncount = pg->GetLength() * 10.0/mfratio;
|
|
|
+ double fstep;
|
|
|
+ if(ncount > 0)fstep = pg->GetLength()/ncount;
|
|
|
+ int i;
|
|
|
+ for(i=1;i<ncount;i++)
|
|
|
+ {
|
|
|
+ double xtem,ytem;
|
|
|
+ xtem = x + (i*fstep)*cos(pg->GetHdg());
|
|
|
+ ytem = y + (i*fstep)*sin(pg->GetHdg());
|
|
|
+ xline.mendx = xtem;
|
|
|
+ xline.mendy = ytem*(-1.0);
|
|
|
+ xline.mE = xline.mE + fstep;
|
|
|
+ xline.mfHdg = pg->GetHdg();
|
|
|
+ CalcPoints(&xline);
|
|
|
+ mvectorline.push_back(xline);
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
|
|
|
+ if(xveclp.size() > 0)
|
|
|
+ {
|
|
|
+ if(xveclp[0].mnLaneSection != nLastSection)
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ if(xlsl.mvectorlanelinese.size() > 0)
|
|
|
+ {
|
|
|
+ if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
|
|
|
+ {
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ xline.mstartx = xtem;
|
|
|
+ xline.mstarty = ytem*(-1.0);
|
|
|
+ }
|
|
|
+ if(ncount > 1)xline.mE = xline.mE + (pg->GetLength() -(ncount -1)*fstep);
|
|
|
+ else xline.mE = xline.mE + pg->GetLength();
|
|
|
+ xline.mendx = x + pg->GetLength() * cos(pg->GetHdg());
|
|
|
+ xline.mendy = (y + pg->GetLength() * sin(pg->GetHdg()))*(-1.0);
|
|
|
+
|
|
|
+// painter->drawLine(QPoint(x*mnfac,y*mnfac*(-1)),
|
|
|
+// QPoint((x + pg->GetLength() * cos(pg->GetHdg()))*mnfac,(y + pg->GetLength() * sin(pg->GetHdg()))*mnfac*(-1)));
|
|
|
+ CalcPoints(&xline);
|
|
|
+ mvectorline.push_back(xline);
|
|
|
+ }
|
|
|
+ break;
|
|
|
+
|
|
|
+ case 1:
|
|
|
+ pSpiral = (GeometrySpiral * )pg;
|
|
|
+ {
|
|
|
+ int ncount = pSpiral->GetLength() * mfratio;
|
|
|
+ if(ncount < 2)ncount = 2;
|
|
|
+ double sstep = pSpiral->GetLength()/((double)ncount);
|
|
|
+ int k;
|
|
|
+ double x0,y0,hdg0,s0;
|
|
|
+ x0 = pSpiral->GetX();
|
|
|
+ y0 = pSpiral->GetY();
|
|
|
+ s0 = pSpiral->GetS();
|
|
|
+ hdg0 = pSpiral->GetHdg() ;
|
|
|
+ pSpiral->GetCoords(s0,rel_x,rel_y,rel_hdg);
|
|
|
+
|
|
|
+ x = rel_x;
|
|
|
+ y = rel_y;
|
|
|
+ xline.mstartx = x;
|
|
|
+ xline.mstarty = y *(-1.0);
|
|
|
+ for(k=1;k<=ncount;k++)
|
|
|
+ {
|
|
|
+ pSpiral->GetCoords(s0+sstep*k,rel_x,rel_y,rel_hdg);
|
|
|
+
|
|
|
+ x = rel_x;
|
|
|
+ y = rel_y;
|
|
|
+ xline.mendx = x;
|
|
|
+ xline.mendy = y*(-1.0);
|
|
|
+ xline.mE = xline.mE + sstep *k;
|
|
|
+ xline.mfHdg = xodrfunc::CalcHdg(QPointF(xline.mstartx,xline.mstarty*(-1)),QPointF(xline.mendx,xline.mendy*(-1)));
|
|
|
+ CalcPoints(&xline);
|
|
|
+ mvectorline.push_back(xline);
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
|
|
|
+ if(xveclp.size() > 0)
|
|
|
+ {
|
|
|
+ if(xveclp[0].mnLaneSection != nLastSection)
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ if(xlsl.mvectorlanelinese.size() > 0)
|
|
|
+ {
|
|
|
+ if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
|
|
|
+ {
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ xline.mstartx = x;
|
|
|
+ xline.mstarty = y*(-1.0);
|
|
|
+
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+// qDebug("spi");
|
|
|
+ break;
|
|
|
+ case 2:
|
|
|
+ {
|
|
|
+ parc = (GeometryArc *)pg;
|
|
|
+ R = abs(1.0/parc->GetCurvature());
|
|
|
+ if(parc->GetCurvature() > 0)
|
|
|
+ {
|
|
|
+ x_center = pg->GetX() + R *cos(pg->GetHdg() + M_PI/2.0);
|
|
|
+ y_center = pg->GetY() + R * sin(pg->GetHdg() + M_PI/2.0);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ x_center = pg->GetX() + R *cos(pg->GetHdg() -M_PI/2.0);
|
|
|
+ y_center = pg->GetY() + R * sin(pg->GetHdg() - M_PI/2.0);
|
|
|
+ }
|
|
|
+
|
|
|
+ int k;
|
|
|
+ int ncount = parc->GetLength() * 3.0/mfratio;
|
|
|
+ if(ncount< 2)ncount = 2;
|
|
|
+ double curv = parc->GetCurvature();
|
|
|
+ double hdgstep;
|
|
|
+ double hdg0 = parc->GetHdg();
|
|
|
+ double hdgnow = parc->GetHdg();
|
|
|
+ if(ncount > 0) hdgstep= (parc->GetLength()/R)/ncount;
|
|
|
+
|
|
|
+ double x_draw,y_draw;
|
|
|
+
|
|
|
+ if(curv > 0)
|
|
|
+ {
|
|
|
+ hdgnow = hdg0 ;
|
|
|
+ x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
|
|
|
+ y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ hdgnow = hdg0;
|
|
|
+ x_draw = x_center + R *cos(hdgnow + M_PI/2.0);
|
|
|
+ y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ xline.mstartx = x_draw;
|
|
|
+ xline.mstarty = y_draw *(-1.0);
|
|
|
+
|
|
|
+ for(k=1;k<=ncount;k++)
|
|
|
+ {
|
|
|
+
|
|
|
+
|
|
|
+ if(curv > 0)
|
|
|
+ {
|
|
|
+ hdgnow = hdg0 + k*hdgstep;
|
|
|
+ x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
|
|
|
+ y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ hdgnow = hdg0 - k * hdgstep;
|
|
|
+ x_draw = x_center + R *cos(hdgnow + M_PI/2.0);
|
|
|
+ y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
|
|
|
+ }
|
|
|
+ xline.mendx = x_draw;
|
|
|
+ xline.mendy = y_draw*(-1.0);
|
|
|
+ xline.mE = xline.mE + hdgstep * R;
|
|
|
+ CalcPoints(&xline);
|
|
|
+ xline.mfHdg = xodrfunc::CalcHdg(QPointF(xline.mstartx,xline.mstarty*(-1)),QPointF(xline.mendx,xline.mendy*(-1)));
|
|
|
+ mvectorline.push_back(xline);
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
|
|
|
+ if(xveclp.size() > 0)
|
|
|
+ {
|
|
|
+ if(xveclp[0].mnLaneSection != nLastSection)
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ if(xlsl.mvectorlanelinese.size() > 0)
|
|
|
+ {
|
|
|
+ if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
|
|
|
+ {
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ xline.mstartx = x_draw;
|
|
|
+ xline.mstarty = y_draw*(-1.0);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ break;
|
|
|
+ case 4:
|
|
|
+ {
|
|
|
+ ppp3 = (GeometryParamPoly3 * )pg;
|
|
|
+ int ncount = ppp3->GetLength()* 3.0/ mfratio;
|
|
|
+ if(ncount < 2)ncount = 2;
|
|
|
+ double sstep;
|
|
|
+ if(ncount > 0)sstep = ppp3->GetLength()/ncount;
|
|
|
+ else sstep = 10000.0;
|
|
|
+ double s = 0;
|
|
|
+ double xtem,ytem;
|
|
|
+ xtem = ppp3->GetuA() + ppp3->GetuB() * s + ppp3->GetuC() * s*s + ppp3->GetuD() * s*s*s;
|
|
|
+ ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
|
|
|
+ x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
|
|
|
+ y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
|
|
|
+ s = s+ sstep;
|
|
|
+ xline.mstartx = x;
|
|
|
+ xline.mstarty = y *(-1.0);
|
|
|
+ while(s <= ppp3->GetLength())
|
|
|
+ {
|
|
|
+
|
|
|
+ xtem = ppp3->GetuA() + ppp3->GetuB() * s + ppp3->GetuC() * s*s + ppp3->GetuD() * s*s*s;
|
|
|
+ ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
|
|
|
+ x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
|
|
|
+ y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
|
|
|
+ xline.mendx = x;
|
|
|
+ xline.mendy = y*(-1.0);
|
|
|
+ xline.mE = xline.mE + sstep;
|
|
|
+ CalcPoints(&xline);
|
|
|
+ xline.mfHdg = xodrfunc::CalcHdg(QPointF(xline.mstartx,xline.mstarty*(-1)),QPointF(xline.mendx,xline.mendy*(-1)));
|
|
|
+ mvectorline.push_back(xline);
|
|
|
+ if(mbShowLane)
|
|
|
+ {
|
|
|
+ std::vector<iv::LanePoint> xveclp = xodrfunc::GetAllLanePoint(mpRoad,xline.mE,xline.mendx,xline.mendy*(-1.0),xline.mfHdg);
|
|
|
+ if(xveclp.size() > 0)
|
|
|
+ {
|
|
|
+ if(xveclp[0].mnLaneSection != nLastSection)
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ if(xlsl.mvectorlanelinese.size() > 0)
|
|
|
+ {
|
|
|
+ if((xlsl.mvectorlanelinese[0].mvectorlanepoint.size() > 0)&&(xlsl.mvectorlanelinese[0].mvectorlanepoint.size() == xveclp.size()))
|
|
|
+ {
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+ iv::lanesectionpoint xvecsp;
|
|
|
+ xvecsp.mvectorlanepoint = xveclp;
|
|
|
+ xlsl.mnsec = xveclp[0].mnLaneSection;
|
|
|
+ nLastSection =xlsl.mnsec;
|
|
|
+ xlsl.mvectorlanelinese.push_back(xvecsp);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ xline.mstartx = x;
|
|
|
+ xline.mstarty = y*(-1.0);
|
|
|
+ s = s+ sstep;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ break;
|
|
|
+ default:
|
|
|
+ break;
|
|
|
+ }
|
|
|
+
|
|
|
+// painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ mvectorlaneline.push_back(xlsl);
|
|
|
+
|
|
|
+ CalcMaxMin();
|
|
|
+
|
|
|
+ mbNeedCalc = false;
|
|
|
+ mfoldcalratio = mfratio;
|
|
|
+
|
|
|
+ return;
|
|
|
+
|
|
|
+ if(mvectorline.size()<0)return;
|
|
|
+ if(mvectorline.size() <= 2)
|
|
|
+ {
|
|
|
+ mtextx = (mvectorline[0].mstartx + mvectorline[0].mendx)/2.0;
|
|
|
+ mtexty = (mvectorline[0].mstarty + mvectorline[0].mendy)/2.0;
|
|
|
+ }
|
|
|
+ else
|
|
|
+ {
|
|
|
+ int i;
|
|
|
+ mtextx = mvectorline[0].mendx;
|
|
|
+ mtexty = mvectorline[0].mendy;
|
|
|
+ for(i=0;i<mvectorline.size();i++)
|
|
|
+ {
|
|
|
+ qDebug("run i is %d size is %d ",i,mvectorline.size());
|
|
|
+ if(mvectorline[i].mE >= (mpRoad->GetRoadLength()/2.0))
|
|
|
+ {
|
|
|
+ mtextx = mvectorline[i].mendx;
|
|
|
+ mtexty = mvectorline[i].mendy;
|
|
|
+ break;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::setratio(float ratio)
|
|
|
+{
|
|
|
+ mfratio = ratio;
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::CalcPoints(iv::lineviewdata *plinedata)
|
|
|
+{
|
|
|
+ float fwidth = mfwidth * mfratio;
|
|
|
+ double fhdg = geofit::CalcHdg(plinedata->mstartx,plinedata->mstarty,plinedata->mendx,plinedata->mendy);
|
|
|
+ plinedata->mPoints[0].setX(plinedata->mstartx + fwidth * cos(fhdg -M_PI/2.0)/2.0 );
|
|
|
+ plinedata->mPoints[0].setY((plinedata->mstarty + fwidth * sin(fhdg -M_PI/2.0)/2.0 )*(1.0));
|
|
|
+ plinedata->mPoints[1].setX(plinedata->mendx + fwidth * cos(fhdg -M_PI/2.0)/2.0 );
|
|
|
+ plinedata->mPoints[1].setY((plinedata->mendy + fwidth * sin(fhdg -M_PI/2.0)/2.0 )*(1.0));
|
|
|
+ plinedata->mPoints[2].setX(plinedata->mendx + fwidth * cos(fhdg +M_PI/2.0)/2.0 );
|
|
|
+ plinedata->mPoints[2].setY((plinedata->mendy + fwidth * sin(fhdg +M_PI/2.0)/2.0 )*(1.0));
|
|
|
+ plinedata->mPoints[3].setX(plinedata->mstartx + fwidth * cos(fhdg +M_PI/2.0)/2.0 );
|
|
|
+ plinedata->mPoints[3].setY((plinedata->mstarty + fwidth * sin(fhdg +M_PI/2.0)/2.0 )*(1.0));
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::CalcMaxMin()
|
|
|
+{
|
|
|
+ if(mvectorline.size()<1)return;
|
|
|
+ mfxmax = mvectorline[0].mstartx;
|
|
|
+ mfxmin = mvectorline[0].mstartx;
|
|
|
+ mfymax = mvectorline[0].mstarty;
|
|
|
+ mfymin = mvectorline[0].mstarty;
|
|
|
+ int i;
|
|
|
+ int nsize = mvectorline.size();
|
|
|
+ if(nsize < 1)return;
|
|
|
+ mtextx = mvectorline[0].mendx;
|
|
|
+ mtexty = mvectorline[0].mendy;
|
|
|
+ bool bFindTextPos = false;
|
|
|
+ for(i=0;i<nsize;i++)
|
|
|
+ {
|
|
|
+ double x,y;
|
|
|
+ x = mvectorline[i].mstartx;
|
|
|
+ y = mvectorline[i].mstarty;
|
|
|
+ if(mfxmin> x)mfxmin = x;
|
|
|
+ if(mfymin > y)mfymin = y;
|
|
|
+ if(mfxmax < x)mfxmax = x;
|
|
|
+ if(mfymax < y)mfymax = y;
|
|
|
+ x = mvectorline[i].mendx;
|
|
|
+ y = mvectorline[i].mendy;
|
|
|
+ if(mfxmin> x)mfxmin = x;
|
|
|
+ if(mfymin > y)mfymin = y;
|
|
|
+ if(mfxmax < x)mfxmax = x;
|
|
|
+ if(mfymax < y)mfymax = y;
|
|
|
+
|
|
|
+ if(bFindTextPos == false)
|
|
|
+ {
|
|
|
+// double xE = mvectorline[i].mE;
|
|
|
+ if(mvectorline[i].mE >= (mpRoad->GetRoadLength()/2.0))
|
|
|
+ {
|
|
|
+ mtextx = mvectorline[i].mendx;
|
|
|
+ mtexty = mvectorline[i].mendy;
|
|
|
+ bFindTextPos = true;
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::setmark(bool bMark)
|
|
|
+{
|
|
|
+ mbMark = bMark;
|
|
|
+}
|
|
|
+
|
|
|
+Road * roadviewitem::GetRoad()
|
|
|
+{
|
|
|
+ return mpRoad;
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::setlaneshow(bool bShow)
|
|
|
+{
|
|
|
+ mbShowLane = bShow;
|
|
|
+ mbNeedCalc = true;
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::setroadidshow(bool bShow)
|
|
|
+{
|
|
|
+ mbShowRoadID = bShow;
|
|
|
+// mbNeedCalc = true;
|
|
|
+}
|
|
|
+
|
|
|
+void roadviewitem::setlineshow(bool bShow)
|
|
|
+{
|
|
|
+ mbShowLine = bShow;
|
|
|
+}
|