Browse Source

delete build_partial.sh

fujiankuan 4 years ago
parent
commit
894ff1cde5

+ 3 - 0
.gitignore

@@ -1,6 +1,9 @@
 # ---> Qt
 # C++ objects and libs
 
+build_partial.sh
+deploy.sh
+
 *.slo
 *.lo
 *.o

+ 0 - 69
build_partial.sh

@@ -1,69 +0,0 @@
-#!/bin/bash
-
-<<<<<<< Updated upstream
-#qtmake="/opt/Qt5.10.1/5.10.1/gcc_64/bin/qmake"
-#qtmake=/usr/bin/qmake
-=======
->>>>>>> Stashed changes
-qtmake="/usr/lib/aarch64-linux-gnu/qt5/bin/qmake"
-
-check_result()
-{
-	 
-	if [ "$1" != 0 ];then
-    	echo -e "\e[33m*************************************************\e[0m"
-    	echo -e "\e[31m    Please modify build error first,Exit!\e[0m"
-    	echo -e "\e[33m*************************************************\e[0m"
- 	   	exit 1
-    fi
-
-}
-
-module=$1
-echo -e "\e[33m module name: \e[1;33m $module \e[0m"
-
-projectDir=`pwd`
-echo -e "project folder \e[33m$projectDir\e[0m"
-
-MAKEOPT=-j8
-
-mkdir bin
-outputDir=$projectDir"/bin"
-echo -e "output folder \e[33m$outputDir\e[0m"
-
-cd src
-sourceDir=`pwd`
-echo -e "source code folder \e[33m$sourceDir\e[0m"
-
-moduleDir=`find . -type d -name $module`
-if [ $moduleDir ];then
-	moduleDir=$sourceDir${moduleDir#*.}
-	echo -e "module code folder \e[33m$moduleDir\e[0m"
-	cd $moduleDir
-	moduleName=$module".pro"
-	echo -e "\e[1;35;47m START BUILD\e[0m"
-	$qtmake $moduleName
-	make $MAKEOPT
-	check_result $? 
-	make clean
-	cp $module $outputDir
-	rm Makefile
-	rm .qmake.stash
-	rm $module
-	cd $projectDir
-	echo -e "\e[1;33;44m Build $module Success \e[0m"
-	sleep 1
-
-	echo -e "\e[35m Start deploy\e[0m"
-	cp $outputDir"/"$module ./
-	bash deploy.sh $module
-	if [ "$?" == 1 ];then
-		exit 1
-	fi
-	rm $module
-	echo -e "\e[1;33;44m Deploy $module Success \e[0m"
-
-else
-	echo -e "\e[31m Can't find module code, exit.....\e[0m"
-	exit
-fi

+ 62 - 0
src/detection/detection_radar_delphi_esr_send/can_send_data_struct.h

@@ -0,0 +1,62 @@
+#ifndef CAN_SEND_DATA_STRUCT_H
+#define CAN_SEND_DATA_STRUCT_H
+
+struct canBit4F0
+{
+    unsigned char ;
+    unsigned char ;
+
+    unsigned char ;
+    unsigned char ;
+
+    unsigned char ;
+    unsigned char ;
+
+
+    unsigned char ;
+    unsigned char ;
+
+    unsigned char ;
+    unsigned char ;
+
+    unsigned char ;
+    unsigned char ;
+};
+union canSend4F0
+{
+    canBit4F0 bit;
+    unsigned char byte[8];
+};
+
+struct canBit4F1
+{
+
+    unsigned char byte[8];
+};
+union canSend4F1
+{
+    canBit4F1 bit;
+    unsigned char byte[8];
+};
+
+struct canBit5F2
+{
+    unsigned char byte[8];
+};
+union canSend5F2
+{
+    canBit5F2 bit;
+    unsigned char byte[8];
+};
+
+
+struct canBit5F4
+{
+    unsigned char byte[8];
+};
+union canSend5F4
+{
+    canBit5F4 bit;
+    unsigned char byte[8];
+};
+#endif // CAN_SEND_DATA_STRUCT_H

+ 2 - 1
src/detection/detection_radar_delphi_esr_send/detection_radar_delphi_esr_send.pro

@@ -24,7 +24,8 @@ HEADERS += \
     ../../include/msgtype/canmsg.pb.h \
     ../../include/msgtype/canraw.pb.h \
     ../../include/msgtype/gpsimu.pb.h \
-    ../../include/msgtype/can_car.pb.h
+    ../../include/msgtype/can_car.pb.h \
+    can_send_data_struct.h
 
 SOURCES += main.cpp \
     ../../include/msgtype/radarobject.pb.cc \

+ 181 - 1
src/driver/driver_map_xodrload/globalplan.cpp

@@ -624,6 +624,184 @@ int GetNearPoint(const double x,const double y,OpenDrive * pxodr,Road ** pObjRoa
     return 0;
 }
 
+
+int GetNearPointWithHead(const double x,const double y,const double hdg,OpenDrive * pxodr,Road ** pObjRoad,GeometryBlock ** pgeo, double & s,double & nearx,
+                 double & neary,double & nearhead,const double nearthresh)
+{
+
+    double dismin = std::numeric_limits<double>::infinity();
+    s = dismin;
+    int i;
+    std::vector<Road * > xvectorroad;
+    std::vector<double > xvectordismin;
+    std::vector<double > xvecotrnearx;
+    std::vector<double > xvectorneary;
+    std::vector<double > xvectornearhead;
+    std::vector<double > xvectors;
+    std::vector<GeometryBlock *> xvectorgeob;
+    double VECTORTHRESH = 5;
+    for(i=0;i<pxodr->GetRoadCount();i++)
+    {
+        int j;
+        Road * proad = pxodr->GetRoad(i);
+        double nx,ny,nh;
+
+        bool bchange = false;
+        double localdismin = std::numeric_limits<double>::infinity();
+
+        double localnearx = 0;
+        double localneary = 0;
+        double localnearhead = 0;
+        double locals = 0;
+        GeometryBlock * pgeolocal;
+
+        for(j=0;j<proad->GetGeometryBlockCount();j++)
+        {
+            GeometryBlock * pgb = proad->GetGeometryBlock(j);
+            double dis;
+            RoadGeometry * pg;
+            pg = pgb->GetGeometryAt(0);
+
+            switch (pg->GetGeomType()) {
+            case 0:   //line
+                dis = GetLineDis((GeometryLine *) pg,x,y,nx,ny,nh);
+                break;
+            case 1:
+                dis = GetSpiralDis((GeometrySpiral *)pg,x,y,nx,ny,nh);
+                break;
+            case 2:  //arc
+                dis = GetArcDis((GeometryArc *)pg,x,y,nx,ny,nh);
+                break;
+
+            case 3:
+                dis = 100000.0;
+                break;
+            case 4:
+                dis = GetParamPoly3Dis((GeometryParamPoly3 *)pg,x,y,nx,ny,nh);
+                break;
+            default:
+                dis = 100000.0;
+                break;
+            }
+
+            if(dis < dismin)
+            {
+                dismin = dis;
+                nearx = nx;
+                neary = ny;
+                nearhead = nh;
+                s = dis;
+                *pObjRoad = proad;
+                *pgeo = pgb;
+
+            }
+
+            if((dis<VECTORTHRESH) &&(dis<localdismin))
+            {
+                localdismin = dis;
+                localnearx = nx;
+                localneary = ny;
+                localnearhead = nh;
+                locals = dis;
+                pgeolocal = pgb;
+                bchange = true;
+            }
+
+
+
+
+        }
+
+        if(bchange)
+        {
+            xvectorroad.push_back(proad);
+            xvecotrnearx.push_back(localnearx);
+            xvectorneary.push_back(localneary);
+            xvectordismin.push_back(localdismin);
+            xvectors.push_back(locals);
+            xvectorgeob.push_back(pgeolocal);
+            xvectornearhead.push_back(localnearhead);
+        }
+    }
+
+
+    if(s > nearthresh)return -1;
+
+    if((*pObjRoad)->GetLaneSectionCount()>0)
+    {
+        LaneSection * pLS = (*pObjRoad)->GetLaneSection(0);
+        if((*pObjRoad)->GetLaneSection(0)->GetLeftLaneCount()&&(*pObjRoad)->GetLaneSection(0)->GetRightLaneCount()>0)
+        {
+            return 0;
+        }
+        else
+        {
+            double headdiff = hdg - nearhead;
+            while(headdiff < 2.0*M_PI) headdiff = headdiff + 2.0*M_PI;
+            while(headdiff >= 2.0*M_PI)headdiff = headdiff - 2.0*M_PI;
+            if(((headdiff <M_PI/2.0)||(headdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
+            {
+               return 0;
+            }
+            else
+            {
+                if((headdiff >=M_PI/2.0)&&(headdiff <= M_PI*3.0/2.0)&&(pLS->GetLeftLaneCount()>0))
+                {
+                    return 0;
+                }
+                else
+                {
+                    bool bHaveSame = false;
+                    for(i=0;i<xvectorroad.size();i++)
+                    {
+                        if(xvectorroad[i]->GetLaneSectionCount()<1)continue;
+                        bool bNeedFind = false;
+                        if(bHaveSame == false)bNeedFind = true;
+                        else
+                        {
+                            if(xvectordismin[i]<dismin)bNeedFind = true;
+                        }
+                        if(bNeedFind)
+                        {
+                            double fdiff = hdg - xvectornearhead[i];
+                            while(fdiff < 2.0*M_PI) fdiff = fdiff + 2.0*M_PI;
+                            while(fdiff >= 2.0*M_PI)fdiff = fdiff - 2.0*M_PI;
+
+                            bool bUse = false;
+                            LaneSection * pLS = xvectorroad[i]->GetLaneSection(0);
+                            if(((fdiff <M_PI/2.0)||(fdiff > M_PI*3.0/2.0))&&(pLS->GetRightLaneCount()>0))
+                            {
+                                bUse = true;
+                            }
+                            if(((fdiff >=M_PI/2.0)&&(fdiff <= M_PI*3.0/2.0))&&(pLS->GetLeftLaneCount()>0))
+                            {
+                                bUse = true;
+                            }
+
+                            if(bUse)
+                            {
+                                dismin = xvectordismin[i];
+                                nearx = xvecotrnearx[i];
+                                neary = xvectorneary[i];
+                                nearhead = xvectornearhead[i];
+                                s = xvectors[i];
+                                *pObjRoad = xvectorroad[i];
+                                *pgeo = xvectorgeob[i];
+                                bHaveSame = true;
+                                std::cout<<"change road. "<<std::endl;
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+
+    return 0;
+}
+
+
+
 /**
   * @brief SelectRoadLeftRight
   * 选择左侧道路或右侧道路
@@ -2026,7 +2204,9 @@ int MakePlan(xodrdijkstra * pxd,OpenDrive * pxodr,const double x_now,const doubl
     double  s;double nearx;
     double  neary;double  nearhead;
     Road * pRoad;GeometryBlock * pgeob;
-    int nfind = GetNearPoint(x_now,y_now,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
+//    int nfind = GetNearPoint(x_now,y_now,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
+
+    int nfind = GetNearPointWithHead(x_now,y_now,head,pxodr,&pRoad,&pgeob,s,nearx,neary,nearhead,srcnearthresh);
 
     if(nfind < 0)return -1;
 

+ 73 - 0
src/driver/driver_ntrip_client/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 35 - 0
src/driver/driver_ntrip_client/driver_ntrip_client.pro

@@ -0,0 +1,35 @@
+QT -= gui
+
+QT += network  serialport
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+#DEFINES += DEBUG_NTRIP_MSG
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+        main.cpp \
+        ntrip_client.cpp
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+HEADERS += \
+    ntrip_client.h

+ 11 - 0
src/driver/driver_ntrip_client/driver_ntrip_client.xml

@@ -0,0 +1,11 @@
+<xml>	
+	<node name="driver_ntrip_client">
+		<param name="ip" value="60.205.8.49" />
+		<param name="port" value="8003" />
+		<param name="mountpoint" value="RTCM32_GGB" />
+		<param name="username" value="xxxx" />
+		<param name="password" value="xxxx" />
+		<param name="devname" value="/dev/ttyUSB0" />
+		<param name="baudrate" value="115200" />
+	</node>
+</xml>

+ 31 - 0
src/driver/driver_ntrip_client/main.cpp

@@ -0,0 +1,31 @@
+#include <QCoreApplication>
+
+#include "ntrip_client.h"
+
+#include "xmlparam.h"
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+    std::string  strip,strport,strmountpoint,strusername,strpassword,strdevname,strbuadrate;
+    QString strpath = QCoreApplication::applicationDirPath();
+    if(argc < 2)
+        strpath = strpath + "/driver_ntrip_client.xml";
+    else
+        strpath = argv[1];
+    std::cout<<strpath.toStdString()<<std::endl;
+    iv::xmlparam::Xmlparam xp(strpath.toStdString());
+    strip = xp.GetParam("ip","60.205.8.49");
+    strport = xp.GetParam("port","8003");
+    strmountpoint = xp.GetParam("mountpoint","RTCM32_GGB");
+    strusername = xp.GetParam("username","xxxxx");
+    strpassword = xp.GetParam("password","xxxxx");
+    strdevname = xp.GetParam("devname","/dev/ttyUSB0");
+    strbuadrate = xp.GetParam("baudrate","115200");
+
+    ntrip_client xntrip(strip,strport,strmountpoint,strusername,strpassword,strdevname,atoi(strbuadrate.data()));
+    (void)&xntrip;
+
+    return a.exec();
+}

+ 253 - 0
src/driver/driver_ntrip_client/ntrip_client.cpp

@@ -0,0 +1,253 @@
+#include "ntrip_client.h"
+
+ntrip_client::ntrip_client(std::string strip,std::string strport,std::string strMountPoint,
+                           std::string strUserName,std::string strPassWord,
+                           std::string strCOMName,int nBaudRate )
+{
+    mstrip = strip;
+    mstrport = strport;
+    mstrMountPoint = strMountPoint;
+    mstrUserName = strUserName;
+    mstrPassWord = strPassWord;
+    mstrCOMName = strCOMName;
+    mnBaudRate = nBaudRate;
+
+    socket_ = new QTcpSocket(this);
+//    socket_->connectToHost("rtk.ntrip.qxwz.com",8002);
+    connect(socket_, SIGNAL(connected()), this, SLOT(connectedSlot()));
+    connect(socket_, SIGNAL(disconnected()), this, SLOT(disconnectedSlot()));
+    connect(socket_, SIGNAL(readyRead()), this, SLOT(readyReadSlot()));
+    connect(socket_, SIGNAL(error(QAbstractSocket::SocketError)), this,
+            SLOT(errorSlot(QAbstractSocket::SocketError)));
+
+    mpTimerNtrip = new QTimer(this);
+    connect(mpTimerNtrip,SIGNAL(timeout()),this,SLOT(onTimerNtrip()));
+    mpTimerNtrip->setInterval(1000);
+    mpTimerNtrip->start();
+
+    mpTimerPort = new QTimer(this);
+    connect(mpTimerPort,SIGNAL(timeout()),this,SLOT(onTimerPortOpen()));
+    mpTimerPort->start(100);
+}
+
+void ntrip_client::run()
+{
+
+}
+
+
+void ntrip_client::connectedSlot()
+{
+    if(socket_->state() == QAbstractSocket::ConnectedState)
+    {
+        qDebug("main is connected.\n");
+        mFindCMState = 3;
+    }
+    else
+    {
+        qDebug("main is not connected.\n");
+    }
+    isConnected_ = true;
+}
+
+void ntrip_client::disconnectedSlot()
+{
+//    qDebug("connect server fail.");
+    if(mFindCMState != -1)mFindCMState = 0;
+    isConnected_ = false;
+    socket_->close();
+
+}
+
+void ntrip_client::readyReadSlot()
+{
+    char * str;
+
+    QByteArray message = socket_->readAll();
+//    qDebug(message.data());
+
+    switch (mFindCMState) {
+
+    case 4:
+        str = (char *)message.data();
+        if(strstr(str,"ICY 200 OK") > 0)
+        {
+            mFindCMState = 5;
+            qDebug("Login succcess");
+        }
+        else
+        {
+            if(strstr(str,"HTTP 401 Unauthorized") > 0)
+            {
+                mFindCMState = -1;
+                qDebug("Authorize Fail. message is %s",message.data());
+            }
+         //   mFindCMState = 0;
+        }
+        break;
+    case 5:
+#ifdef  DEBUG_NTRIP_MSG
+        ShowNtripMsg(message);
+#else
+        qDebug("ntrip msg len is %d",message.length());
+#endif
+
+        if(mbPortOpen)
+        {
+            if(-1 == m_serialPort_RTK->write(message))
+            {
+                qDebug("Write Serial Port Fail.");
+                m_serialPort_RTK->close();
+                mbPortOpen = false;
+                mpTimerPort->start(100);
+            }
+        }
+
+        break;
+    default:
+        break;
+    }
+
+
+//    qDebug("len = %d",message.length());
+/*
+    char strX[3000],strX2[10];
+    int i;
+    int nLen = message.length();
+    snprintf(strX,3000,"");
+    for(i=0;i<nLen;i++)
+    {
+        unsigned char * p = (unsigned char *)(message.data()+i);
+        snprintf(strX2,10,"%02X ",*p);strncat(strX,strX2,3000);
+    }
+    qDebug(strX);*/
+//    qDebug("TIME = %d read meesage length = %d",mTime.elapsed() ,message.length());
+
+
+
+}
+
+void ntrip_client::errorSlot(QAbstractSocket::SocketError)
+{
+//    QMessageBox::information(this, "show", socket_->errorString());
+    disconnectedSlot();
+}
+
+
+void ntrip_client::onTimerNtrip()
+{
+    switch (mFindCMState) {
+    case -1:
+        mpTimerPort->stop();
+        mpTimerNtrip->stop();
+        qDebug("User Pass Word Error.");
+        if(mbPortOpen)m_serialPort_RTK->close();
+        break;
+    case 0:
+        socket_->connectToHost(mstrip.data(),atoi(mstrport.data()));
+        mFindCMState = 1;
+        break;
+    case 2:
+        break;
+    case 3:
+        SendUserPass();
+        mFindCMState = 4;
+        break;
+    case 4:
+        break;
+    case 5:
+        SendGPGGA();
+        break;
+    default:
+        break;
+    }
+}
+
+void ntrip_client::SendUserPass()
+{
+    char strSend[1000];
+ //   snprintf(strSend,1000,"GET / HTTP/1.0\r\nUser-Agent: NTRIP GNSSInternetRadio/1.4.10\r\nAccept: */*\r\nConnection: close\r\n\r\n");
+    char strLine[100];
+    char strX[1000];
+    snprintf(strX,1000,"%s:%s",mstrUserName.data(),mstrPassWord.data());
+    QByteArray ba; ba.append(strX);qDebug(ba.toBase64().data());
+    snprintf(strSend,1000,"GET /%s HTTP/1.0\r\n",mstrMountPoint.data());
+    snprintf(strLine,100,"User-Agent: NTRIP GNSSInternetRadio/1.4.10\r\n");strncat(strSend,strLine,1000);
+    snprintf(strLine,100,"Accept: */*\r\n");strncat(strSend,strLine,1000);
+    snprintf(strLine,100,"Connection: close\r\n");strncat(strSend,strLine,1000);
+    snprintf(strLine,100,"Authorization: Basic %s\r\n",ba.toBase64().data());strncat(strSend,strLine,1000);
+    snprintf(strLine,100,"\r\n");strncat(strSend,strLine,1000);
+    socket_->write(strSend,strlen(strSend));
+    socket_->flush();
+}
+
+void ntrip_client::SendGPGGA()
+{
+
+
+    if(mbPortOpen)
+    {
+        QByteArray ba = m_serialPort_RTK->read(1000);
+        if(ba.length() > 0)
+        {
+            socket_->write(ba);
+            socket_->flush();
+        }
+    }
+    else
+    {
+#ifdef DEBUG_NTRIP_MSG
+        char strSend[1000];
+        snprintf(strSend,1000,"$GPGGA,102342.00,3948.6248006,N,11633.1924828,E,1,13,1.5,46.4085,M,-9.452,M,99,AAAA*72\r\n");
+        socket_->write(strSend,strlen(strSend));
+        socket_->flush();
+#endif
+    }
+
+/*    char strSend[1000];
+    snprintf(strSend,1000,"$GPGGA,102342.00,3948.6248006,N,11633.1924828,E,1,13,1.5,46.4085,M,-9.452,M,99,AAAA*72\r\n");
+    socket_->write(strSend,strlen(strSend));
+    socket_->flush();*/
+}
+
+void ntrip_client::onTimerPortOpen()
+{
+    if(mbPortOpen)return;
+    m_serialPort_RTK = new QSerialPort();
+    m_serialPort_RTK->setPortName(mstrCOMName.data());
+    m_serialPort_RTK->setBaudRate(mnBaudRate);
+    m_serialPort_RTK->setParity(QSerialPort::NoParity);
+    m_serialPort_RTK->setDataBits(QSerialPort::Data8);
+    m_serialPort_RTK->setStopBits(QSerialPort::OneStop);
+    m_serialPort_RTK->setFlowControl(QSerialPort::NoFlowControl);
+    m_serialPort_RTK->setReadBufferSize(0);
+    if(m_serialPort_RTK->open(QSerialPort::ReadWrite))
+    {
+        mbPortOpen = true;
+        mpTimerPort->stop();
+    }
+    else
+    {
+        qDebug("Open RTK Port Fail. Port Name is %s BaudRate is %d ",mstrCOMName.data(),mnBaudRate);
+        mbPortOpen = false;
+        delete m_serialPort_RTK;
+        mpTimerPort->setInterval(10000);
+
+    }
+
+}
+
+void ntrip_client::ShowNtripMsg(QByteArray ba)
+{
+    char strout[3000];
+    snprintf(strout,3000,"Ntrip msg len is %d info is:",ba.length());
+    char strtem[10];
+    int nlen = ba.length();
+    int i;
+    for(i=0;i<nlen;i++)
+    {
+        snprintf(strtem,10,"%02X ",(unsigned char )ba.at(i));
+        strncat(strout,strtem,3000);
+    }
+    qDebug(strout);
+}

+ 71 - 0
src/driver/driver_ntrip_client/ntrip_client.h

@@ -0,0 +1,71 @@
+#ifndef NTRIP_CLIENT_H
+#define NTRIP_CLIENT_H
+
+
+#include <QObject>
+#include <QThread>
+#include <QDateTime>
+#include <QTimer>
+#include <iostream>
+
+#include <QSerialPort>
+
+#include <QUdpSocket>
+#include <QNetworkDatagram>
+#include <QtNetwork/QTcpSocket>
+
+
+
+#include "modulecomm.h"
+#include "xmlparam.h"
+
+
+class ntrip_client : public QThread
+{
+        Q_OBJECT
+public:
+    ntrip_client(std::string strip,std::string strport,std::string strMountPoint,
+                 std::string strUserName,std::string strPassWord,
+                 std::string strCOMName,int nBaudRate = 115200);
+
+private slots:
+    void connectedSlot();
+    void disconnectedSlot();
+    void readyReadSlot();
+    void errorSlot(QAbstractSocket::SocketError);
+
+    void onTimerNtrip();
+    void onTimerPortOpen();
+
+private:
+    std::string mstrip;
+    std::string mstrport;
+    std::string mstrMountPoint;
+    std::string mstrUserName;
+    std::string mstrPassWord;
+    std::string mstrCOMName;
+    int mnBaudRate;
+
+    int mFindCMState = 0; //-1 Pass Error 0 not connected 1 connecting 2 connected 3 need send pass 4 had send usernamepassword 5 connected
+    QTcpSocket *socket_;
+    bool isConnected_;
+    int mSerialState;
+
+    QSerialPort *m_serialPort_RTK;
+    bool mbPortOpen = false;
+
+    QTimer * mpTimerNtrip;
+    QTimer * mpTimerPort;
+
+
+private:
+    void SendUserPass();
+    void SendGPGGA();
+
+    void ShowNtripMsg(QByteArray ba);
+
+private:
+    void run();
+};
+
+#endif // NTRIP_CLIENT_H

+ 37 - 3
src/ui/ui_ads_hmi/ADCIntelligentVehicle.cpp

@@ -239,15 +239,22 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     myview->setObjectName(QStringLiteral("graphicsView"));
     myview->setGeometry(QRect(0, 100, 900, 900)); //从屏幕上(0,100)位置开始(即为最左上角的点),显示一个900*900的界面(宽900,高900)
 
+    myview_small = new MyView(ui->stackedWidget->widget(1));
+    myview_small->setObjectName(QStringLiteral("graphicsView_small"));
+    myview_small->setGeometry(QRect(1000,100,450,450));
+
     image = new QImage(900 * 2, 900 * 2, QImage::Format_RGB32);//画布的初始化大小设为600*500,使用32位颜色
     //QImage的32、24、8位图。 图像格式:QImage::Format_RGB32 ,QImage::Format_RGB888,QImage::Format_Indexed8。
     //QImage myImage2 = QImage(width, height, QImage::Format_…); 根据图像宽高来构造一幅图像,程序会自动根据图像格式对齐图像数据。
-
+    image_small = new QImage(900 * 2,900 * 2,QImage::Format_RGB32);
 
     myview->setCacheMode(myview->CacheBackground);
+    myview_small->setCacheMode(myview_small->CacheBackground);
 
     painter = new QPainter(image);   //创建QPainter对象
+    painter_small = new QPainter(image_small);   //创建QPainter对象
     scene = new QGraphicsScene;
+    scene_small = new QGraphicsScene;
     look_decition = new Look_decition;
     mobileye_info = new Mobileye_info;
     timer = new QTimer(this);
@@ -507,6 +514,7 @@ void ADCIntelligentVehicle::timeoutslot()
 
     ui->lb_current_speed_big->setText(QString::number(ServiceCarStatus.speed,'f',1));
 
+
     //    QString is_ok;
     //    is_ok = (ServiceLidar.did_lidar_ok() == true)?QStringLiteral("ok"):QStringLiteral("error");
     //    ui->lineEdit_4->setText(is_ok);
@@ -803,8 +811,10 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         mnTimeLastUpdatePaint = mTime.elapsed();
         //       qDebug("enter paint. time is %d",mTime.elapsed());
         painter->begin(image);
+        painter_small->begin(image_small);
        // image->fill(QColor(60, 60, 60));//对画布进行填充
        image->fill(QColor(220, 220, 220));//对画布进行填充
+       image_small->fill(QColor(220,220,220));
         std::vector<iv::GPSData> navigation_data;
         mMutexNavi.lock();
         navigation_data = m_navigation_data;
@@ -822,8 +832,10 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
 
         //        std::vector<iv::GPSData> navigation_data = brain->navigation_data;
         painter->setRenderHint(QPainter::Antialiasing, true);//设置反锯齿模式,好看一点
+        painter_small->setRenderHint(QPainter::Antialiasing, true);//设置反锯齿模式,好看一点
 
         int pointx = 450, pointy = 700;//确定坐标轴起点坐标,这里定义(35,280)
+        int pointx_small = 450, pointy_small = 700;
         //        double x0[22000], y0[22000], lng[22000], x1[22000], y1[22000], x2[22000], y2[22000];
 
                 double * x0, * y0, * lng, * x1, * y1, * x2, * y2;
@@ -856,13 +868,19 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         //先绘制车位置点及框图
         static const QPointF points1[2] = { QPointF(300, 700), QPointF(600, 700) };
         static const QPointF points2[2] = { QPointF(450, 0), QPointF(450, 900) };
+        static const QPointF points1_small[2] = { QPointF(300, 700), QPointF(600, 700) };
+        static const QPointF points2_small[2] = { QPointF(450, 0), QPointF(450, 900) };
 
         penPoint.setColor(Qt::red);
         penPoint.setWidth(2);
         painter->setPen(penPoint);
+        painter_small->setPen(penPoint);
         painter->drawPoint(pointx, pointy);
+        painter_small->drawPoint(pointx_small,pointy_small);
         painter->drawPolyline(points1, 2);
         painter->drawPolyline(points2, 2);
+        painter_small->drawPolyline(points1_small, 2);
+        painter_small->drawPolyline(points2_small, 2);
 
         //路径点的预处理
         for (int i = 0; i < sizeN; i++)
@@ -897,6 +915,7 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         if (ServiceCarStatus.location->gps_x == 0)
         {
             painter->drawText(rect(), Qt::AlignLeft, QString::fromLocal8Bit("等待车辆实时GPS位置信息"));
+            painter_small->drawText(rect(), Qt::AlignLeft, QString::fromLocal8Bit("等待车辆实时GPS位置信息"));
         }
         else
         {
@@ -923,8 +942,11 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
             y2[i] = y0[i] - k2 * 5;
         }
 
-        double kx = (double)(700) / (abs(y_max - y_min));//x轴的系数
-        double ky = (double)(700) / (abs(y_max - y_min));//y方向的比例系数
+        double kx_small = (double)(600) / (abs(y_max - y_min));//x轴的系数
+        double ky_small = (double)(600) / (abs(y_max - y_min));//y方向的比例系数
+
+        double kx = 10;
+        double ky = 10;
 
         //距离车正前方10m处画一条线
         static const QPointF points3[2] = { QPointF(0, 700 - 10 * ky), QPointF(900, 700 - 10 * ky) };
@@ -937,16 +959,22 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         for (int i = 1; i < sizeN - 1; i++)
         {
             painter->setPen(penPoint);//蓝色的笔,用于标记各个点
+            painter_small->setPen(penPoint);//蓝色的笔,用于标记各个点
             painter->drawPoint(pointx + x0[i] * kx, pointy - y0[i] * ky);
+            painter_small->drawPoint(pointx_small + x0[i] * kx_small, pointy_small - y0[i] * ky_small);
             painter->drawPoint(pointx + x1[i] * kx, pointy - y1[i] * ky);
+            painter_small->drawPoint(pointx_small + x1[i] * kx_small, pointy_small - y1[i] * ky_small);
             painter->drawPoint(pointx + x2[i] * kx, pointy - y2[i] * ky);
+            painter_small->drawPoint(pointx_small + x2[i] * kx_small, pointy_small - y2[i] * ky_small);
         }
         painter->drawPoint(pointx + x0[sizeN - 1] * kx, pointy - y0[sizeN - 1] * ky);//绘制最后一个点
+        painter_small->drawPoint(pointx_small + x0[sizeN - 1] * kx_small, pointy_small - y0[sizeN - 1] * ky_small);//绘制最后一个点
 
         penPoint.setColor(Qt::red);
         penPoint.setWidth(2);
 
         painter->drawPoint(pointx + x0[0] * kx, pointy - y0[0] * ky);
+        painter_small->drawPoint(pointx_small + x0[0] * kx_small, pointy_small - y0[0] * ky_small);
 
         // draw plan trace
         penPoint.setColor(Qt::green);
@@ -969,6 +997,7 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         //pix.load("car.png");
         pix.load(":/ADCIntelligentVehicle/car1.png");
         painter->drawPixmap(435,667,30,67,pix);
+        painter_small->drawPixmap(442,683,16,34,pix);
 ///////////////////////////////////////////////////////////////////
 
 
@@ -1029,10 +1058,15 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
 
 
         painter->end();
+        painter_small->end();
         scene->clear();
+        scene_small->clear();
         scene->addPixmap(QPixmap::fromImage(*image));
+        scene_small->addPixmap(QPixmap::fromImage(*image_small));
         myview->setScene(scene);
+        myview_small->setScene(scene_small);
         myview->show();
+        myview_small->show();
         navigation_data.clear();
 
         if(mfSOC != 0.0)

+ 4 - 4
src/ui/ui_ads_hmi/ADCIntelligentVehicle.h

@@ -231,11 +231,11 @@ private:
     qreal scaleFactor;
     qreal currentStepScaleFactor;
 
-    QImage *image;
-    QPainter *painter;
-    MyView *myview;
+    QImage *image,*image_small;
+    QPainter *painter,*painter_small;
+    MyView *myview,*myview_small;
     QTimer *timer;
-    QGraphicsScene *scene;
+    QGraphicsScene *scene,*scene_small;
     iv::ObsLiDAR Lidar_read;
     iv::ObsLiDAR Lidar_obsread;
     iv::ObsRadar RadarDate;

+ 5 - 5
src/ui/ui_ads_hmi/ADCIntelligentVehicle.ui

@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1046</width>
-    <height>791</height>
+    <width>1900</width>
+    <height>1060</height>
    </rect>
   </property>
   <property name="windowTitle">
@@ -93,7 +93,7 @@
      <rect>
       <x>90</x>
       <y>60</y>
-      <width>900</width>
+      <width>1500</width>
       <height>871</height>
      </rect>
     </property>
@@ -2002,7 +2002,7 @@ p, li { white-space: pre-wrap; }
      <rect>
       <x>-1</x>
       <y>0</y>
-      <width>1051</width>
+      <width>1200</width>
       <height>31</height>
      </rect>
     </property>
@@ -2064,7 +2064,7 @@ p, li { white-space: pre-wrap; }
     <rect>
      <x>0</x>
      <y>0</y>
-     <width>1046</width>
+     <width>1900</width>
      <height>22</height>
     </rect>
    </property>

+ 73 - 0
src/ui/ui_osgviewer/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 1 - 0
src/ui/ui_osgviewer/Readme.md

@@ -0,0 +1 @@
+1.本项目参照gitbhub上的esmini工程。

+ 153 - 0
src/ui/ui_osgviewer/gnss_coordinate_convert.cpp

@@ -0,0 +1,153 @@
+#include <gnss_coordinate_convert.h>
+
+void gps2xy(double J4, double K4, double *x, double *y)
+{
+    int L4 = (int)((K4 - 1.5) / 3) + 1;
+    double M4 = K4 - (L4 * 3);
+    double N4 = sin(J4 * 3.1415926536 / 180);
+    double O4 = cos(J4 * 3.1415926536 / 180);
+    double P4 = tan(J4 * 3.1415926536 / 180);
+    double Q4 = 111134.8611 * J4 - N4 * O4 * (32005.7799 + 133.9238 * N4 * N4 + 0.6973 * N4 * N4 * N4 * N4 + 0.0039 * N4 * N4 * N4 * N4 * N4 * N4);
+    double R4 = sqrt(0.006738525414683) * O4;
+    double S4 = sqrt(1 + R4 * R4);
+    double T4 = 6399698.901783 / S4;
+    double U4 = (T4 / S4) / S4;
+    double V4 = O4 * M4 * 3.1415926536 / 180;
+    double W4 = 0.5 + (5 - P4 * P4 + 9 * R4 * R4 + 4 * R4 * R4 * R4 * R4) * V4 * V4 / 24;
+    double X4 = V4 * V4 * V4 * V4 / 720 * (61 + (P4 * P4 - 58) * P4 * P4);
+    double Y4 = 1 + V4 * V4 * (1 - P4 * P4 + R4 * R4) / 6;
+    double Z4 = V4 * V4 * V4 * V4 * (5 - 18 * P4 * P4 * P4 * P4 * P4 * P4 + 14 * R4 * R4 - 58 * R4 * R4 * P4 * P4) / 120;
+
+    *y = Q4 + T4 * P4 * V4 * V4 * (W4 + X4);
+    *x = 500000 + T4 * V4 * (Y4 + Z4);
+}
+
+//高斯投影由经纬度(Unit:DD)反算大地坐标(含带号,Unit:Metres)
+void GaussProjCal(double longitude, double latitude, double *X, double *Y)
+{
+    int ProjNo = 0; int ZoneWide; ////带宽
+    double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
+    double a, f, e2, ee, NN, T, C, A, M, iPI;
+    iPI = 0.0174532925199433; ////3.1415926535898/180.0;
+    ZoneWide = 6; ////6度带宽
+    a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
+                                    ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
+    ProjNo = (int)(longitude / ZoneWide);
+    longitude0 = ProjNo * ZoneWide + ZoneWide / 2;
+    longitude0 = longitude0 * iPI;
+    latitude0 = 0;
+    longitude1 = longitude * iPI; //经度转换为弧度
+    latitude1 = latitude * iPI; //纬度转换为弧度
+    e2 = 2 * f - f * f;
+    ee = e2 * (1.0 - e2);
+    NN = a / sqrt(1.0 - e2 * sin(latitude1)*sin(latitude1));
+    T = tan(latitude1)*tan(latitude1);
+    C = ee * cos(latitude1)*cos(latitude1);
+    A = (longitude1 - longitude0)*cos(latitude1);
+    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
+        *e2 / 1024)*sin(2 * latitude1)
+        + (15 * e2*e2 / 256 + 45 * e2*e2*e2 / 1024)*sin(4 * latitude1) - (35 * e2*e2*e2 / 3072)*sin(6 * latitude1));
+    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);
+    yval = M + NN * tan(latitude1)*(A*A / 2 + (5 - T + 9 * C + 4 * C*C)*A*A*A*A / 24
+        + (61 - 58 * T + T * T + 600 * C - 330 * ee)*A*A*A*A*A*A / 720);
+    X0 = 1000000L * (ProjNo + 1) + 500000L;
+    Y0 = 0;
+    xval = xval + X0; yval = yval + Y0;
+    *X = xval;
+    *Y = yval;
+}
+
+
+
+//=======================zhaobo0904
+#define PI  3.14159265358979
+//void GaussProjCal(double lon, double lat, double *X, double *Y)
+//{
+//    // 1975 年国际椭球体长半轴 a, 第一离心率 e2, 第二离心率 ep2
+//    double a = 6378140.0;
+//    double e2 = 0.006694384999588;
+//    double ep2 = e2/(1-e2);
+
+//    // 原点所在经度
+//    double lon_origin = 6.0*int(lon/6) + 3.0;
+//    lon_origin *= PI / 180.0;
+
+//    double k0 = 0.9996;
+
+//    // 角度转弧度
+//    double lat1 = lat * PI / 180.0;
+//    double lon1 = lon * PI / 180.0;
+
+
+//    // 经线在该点处的曲率半径,
+//    double N = a / sqrt(1 - e2*sin(lat1)*sin(lat1));
+
+
+//    // 赤道到该点的经线长度近似值 M, 使用泰勒展开逐项积分然后取前四项.
+//    // 这个近似值是将 N 作为纬度 \phi 的函数展开为泰勒计数, 然后在区间 [0, lat1] 上积分得到的.
+//    // 首先计算前四项的系数 a1~a4.
+//    double a1 = 1 - e2/4 - (3*e2*e2)/64 - (5*e2*e2*e2)/256;
+//    double a2 = (3*e2)/8 + (3*e2*e2)/32 + (45*e2*e2*e2)/1024;
+//    double a3 = (15*e2*e2)/256 + (45*e2*e2*e2)/1024;
+//    double a4 = (35*e2*e2*e2)/3072;
+//    double M = a * (a1*lat1 - a2*sin(2*lat1) + a3*sin(4*lat1) - a4*sin(6*lat1));
+
+//    // 辅助量
+//    double T = tan(lat1)*tan(lat1);
+//    double C = ep2*cos(lat1)*cos(lat1);
+//    double A = (lon1 - lon_origin)*cos(lat1);
+
+//    *X = 500000.0 + k0 * N * (A + (1 - T + C)*(A*A*A)/6 + (5 - 18*T + T*T + 72*C - 58*ep2)*(A*A*A*A*A)/120);
+//    *Y = M + N * tan(lat1) * ((A*A)/2 +
+//                              (5 - T + 9*C + 4*C*C)*(A*A*A*A)/24 +
+//                              (61 - 58*T + T*T + 600*C - 330*ep2)*(A*A*A*A*A*A)/720);
+
+
+//    *Y *= k0;
+//    return;
+//}
+//==========================================================
+
+
+
+
+
+//高斯投影由大地坐标(Unit:Metres)反算经纬度(Unit:DD)
+void GaussProjInvCal(double X, double Y, double *longitude, double *latitude)
+{
+    int ProjNo; int ZoneWide; ////带宽
+    double longitude1, latitude1, longitude0, latitude0, X0, Y0, xval, yval;
+    double e1, e2, f, a, ee, NN, T, C, M, D, R, u, fai, iPI;
+    iPI = 0.0174532925199433; ////3.1415926535898/180.0;
+    a = 6378245.0; f = 1.0 / 298.3; //54年北京坐标系参数
+    ////a=6378140.0; f=1/298.257; //80年西安坐标系参数
+    ZoneWide = 6; ////6度带宽
+    ProjNo = (int)(X / 1000000L); //查找带号
+    longitude0 = (ProjNo - 1) * ZoneWide + ZoneWide / 2;
+    longitude0 = longitude0 * iPI; //中央经线
+    X0 = ProjNo * 1000000L + 500000L;
+    Y0 = 0;
+    xval = X - X0; yval = Y - Y0; //带内大地坐标
+    e2 = 2 * f - f * f;
+    e1 = (1.0 - sqrt(1 - e2)) / (1.0 + sqrt(1 - e2));
+    ee = e2 / (1 - e2);
+    M = yval;
+    u = M / (a*(1 - e2 / 4 - 3 * e2*e2 / 64 - 5 * e2*e2*e2 / 256));
+    fai = u + (3 * e1 / 2 - 27 * e1*e1*e1 / 32)*sin(2 * u) + (21 * e1*e1 / 16 - 55 * e1*e1*e1*e1 / 32)*sin(
+                4 * u)
+            + (151 * e1*e1*e1 / 96)*sin(6 * u) + (1097 * e1*e1*e1*e1 / 512)*sin(8 * u);
+    C = ee * cos(fai)*cos(fai);
+    T = tan(fai)*tan(fai);
+    NN = a / sqrt(1.0 - e2 * sin(fai)*sin(fai));
+    R = a * (1 - e2) / sqrt((1 - e2 * sin(fai)*sin(fai))*(1 - e2 * sin(fai)*sin(fai))*(1 - e2 * sin
+                                                                                       (fai)*sin(fai)));
+    D = xval / NN;
+    //计算经度(Longitude) 纬度(Latitude)
+    longitude1 = longitude0 + (D - (1 + 2 * T + C)*D*D*D / 6 + (5 - 2 * C + 28 * T - 3 * C*C + 8 * ee + 24 * T*T)*D
+                               *D*D*D*D / 120) / cos(fai);
+    latitude1 = fai - (NN*tan(fai) / R)*(D*D / 2 - (5 + 3 * T + 10 * C - 4 * C*C - 9 * ee)*D*D*D*D / 24
+                                         + (61 + 90 * T + 298 * C + 45 * T*T - 256 * ee - 3 * C*C)*D*D*D*D*D*D / 720);
+    //转换为度 DD
+    *longitude = longitude1 / iPI;
+    *latitude = latitude1 / iPI;
+}

+ 26 - 0
src/ui/ui_osgviewer/gnss_coordinate_convert.h

@@ -0,0 +1,26 @@
+#pragma once
+#ifndef _IV_PERCEPTION_GNSS_CONVERT_
+#define _IV_PERCEPTION_GNSS_CONVERT_
+
+#include <math.h>
+//double nmeaConvert2Lat(string lat)
+//{
+//	Console.WriteLine(lat);
+//	double nmea_d = double.Parse(lat.Substring(0, 2));
+//	double nmea_m = double.Parse(lat.Substring(2, 6));
+//	return nmea_d + nmea_m / 60;
+//}
+//
+//double nmeaConvert2Lon(string lon)
+//{
+//	Console.WriteLine(lon);
+//	double nmea_d = double.Parse(lon.Substring(0, 3));
+//	double nmea_m = double.Parse(lon.Substring(3, 7));
+//	return nmea_d + nmea_m / 60;
+//}
+
+void gps2xy(double , double , double *, double *);
+void GaussProjCal(double longitude, double latitude, double *X, double *Y);
+void GaussProjInvCal(double X, double Y, double *longitude, double *latitude);
+
+#endif // !_IV_PERCEPTION_GNSS_CONVERT_

+ 626 - 0
src/ui/ui_osgviewer/main.cpp

@@ -0,0 +1,626 @@
+	/* 
+ * esmini - Environment Simulator Minimalistic 
+ * https://github.com/esmini/esmini
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this
+ * file, You can obtain one at https://mozilla.org/MPL/2.0/.
+ * 
+ * Copyright (c) partners of Simulation Scenarios
+ * https://sites.google.com/view/simulationscenarios
+ */
+
+ /*
+  * The purpose of this application is to support development of the RoadManager by visualizing the road network and moving objects on top.
+  * Bascially it loads an OpenDRIVE file, and optionally a corresponding 3D model, and then populate vehicles at specified density. The 
+  * vehicles will simply follow it's lane until a potential junction where the choice of route is randomized.
+  *
+  * The application can be used both to debug the RoadManager and to check OpenDRIVE files, e.g. w.r.t. gemoetry, lanes and connectivity.
+  *
+  * New road/track segments is indicated by a yellow large dot. Geometry segments within a road are indicated by red dots.
+  * Red line is the reference lane, blue lines shows drivable lanes. Non-drivable lanes are currently not indicated. 
+  */
+
+#include <random>
+#include <iostream>
+#define _USE_MATH_DEFINES
+#include <math.h>
+
+#include "viewer.hpp"
+#include "RoadManager.hpp"
+#include "CommonMini.hpp"
+
+
+#define DEFAULT_SPEED   70  // km/h
+#define DEFAULT_DENSITY 1   // Cars per 100 m
+#define ROAD_MIN_LENGTH 30
+#define SIGN(X) ((X<0)?-1:1)
+
+
+static bool run_only_once = false;
+static const double stepSize = 0.01;
+static const double maxStepSize = 0.1;
+static const double minStepSize = 0.01;
+static const bool freerun = true;
+static std::mt19937 mt_rand;
+static double density = DEFAULT_DENSITY;
+static double speed = DEFAULT_SPEED;
+static double global_speed_factor = 1.0;
+static int first_car_in_focus = -1;
+
+double deltaSimTime;  // external - used by Viewer::RubberBandCamera
+
+typedef struct
+{
+	int road_id_init;
+	int lane_id_init;
+	double heading_init;
+	double s_init;
+	roadmanager::Position *pos;
+	double speed_factor;  // speed vary bewtween lanes, m/s
+	viewer::EntityModel *model;
+	int id;
+} Car;
+
+std::vector<Car*> cars;
+
+Car * gADCIV_car;
+
+// Car models used for populating the road network
+// path should be relative the OpenDRIVE file
+static const char* carModelsFiles_[] =
+{
+	"car_white.osgb",
+	"car_blue.osgb",
+	"car_red.osgb",
+	"car_yellow.osgb",
+	"truck_yellow.osgb",
+	"van_red.osgb",
+	"bus_blue.osgb",
+};
+
+std::vector<osg::ref_ptr<osg::LOD>> carModels_;
+
+
+
+#include "modulecomm.h"
+#include "gpsimu.pb.h"
+#include "gnss_coordinate_convert.h"
+
+double glat0 = 39.1201777;
+double glon0 = 117.02802270;
+
+double gfrel_x = 0;
+double gfrel_y = 0;
+double gfrel_z = 0;
+double gvehicle_hdg = 0;
+
+double gvehicleheight = 1.6;
+double gfspeed = 0;
+
+
+void Listengpsimu(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+//        ggpsimu->UpdateGPSIMU(strdata,nSize);
+
+    iv::gps::gpsimu xgpsimu;
+    if(!xgpsimu.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"ListenRaw Parse error."<<std::endl;
+        return;
+    }
+    (void)&index;
+    (void)dt;
+    (void)strmemname;
+
+    double x0,y0;
+    double x,y;
+    double rel_x, rel_y;
+    GaussProjCal(glon0,glat0,&x0,&y0);
+    GaussProjCal(xgpsimu.lon(),xgpsimu.lat(),&x,&y);
+    rel_x = x - x0;
+    rel_y = y - y0;
+
+    gfrel_x = rel_x;
+    gfrel_y = rel_y;
+    gfrel_z = xgpsimu.height();
+
+    if(xgpsimu.has_speed())
+    {
+        gfspeed = xgpsimu.speed();
+    }
+    else
+    {
+        gfspeed = 3.6*sqrt(pow(xgpsimu.vn(),2)+pow(xgpsimu.ve(),2));
+    }
+
+    double hdg = xgpsimu.heading();
+    hdg =  (90-hdg) * M_PI/180.0;
+    if(hdg < 0)hdg = hdg + M_PI*2.0;
+    gvehicle_hdg = hdg;
+}
+
+
+void log_callback(const char *str)
+{
+	printf("%s\n", str);
+}
+
+
+#include <osgDB/ReadFile>
+#include <osg/ComputeBoundsVisitor>
+#include <osg/LineWidth>
+#include <osg/Point>
+#include <osg/BlendFunc>
+#include <osg/BlendColor>
+#include <osg/Geode>
+#include <osg/Group>
+#include <osg/ShapeDrawable>
+#include <osg/CullFace>
+#include <osgGA/StateSetManipulator>
+#include <osgGA/TrackballManipulator>
+#include <osgGA/KeySwitchMatrixManipulator>
+#include <osgGA/FlightManipulator>
+#include <osgGA/DriveManipulator>
+#include <osgGA/TerrainManipulator>
+#include <osgGA/SphericalManipulator>
+#include <osgViewer/ViewerEventHandlers>
+#include <osgDB/Registry>
+#include <osgShadow/StandardShadowMap>
+#include <osgShadow/ShadowMap>
+#include <osgShadow/ShadowedScene>
+#include <osgUtil/SmoothingVisitor>
+#include <osgUtil/Tessellator> // to tessellate multiple contours
+
+
+void createosgbox()
+{
+    osg::ref_ptr<osg::Group> group = 0;
+    osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+    geode->addDrawable(new osg::ShapeDrawable(new osg::Box()));
+
+    osg::ref_ptr<osg::Group> bbGroup = new osg::Group;
+    osg::ref_ptr<osg::PositionAttitudeTransform> tx = new osg::PositionAttitudeTransform;
+
+    osg::Material* material = new osg::Material();
+
+    // Set color of vehicle based on its index
+    double* color;
+    double b = 1.5;  // brighness
+    int index = 2;
+
+    if (index == 0) color = color_white;
+    else if (index == 1) color = color_red;
+    else if (index == 2) color = color_blue;
+    else color = color_yellow;
+
+    material->setDiffuse(osg::Material::FRONT, osg::Vec4(b * color[0], b * color[1], b * color[2], 1.0));
+    material->setAmbient(osg::Material::FRONT, osg::Vec4(b * color[0], b * color[1], b * color[2], 1.0));
+
+    osg::ref_ptr<osg::Geode> geodeCopy = dynamic_cast<osg::Geode*>(geode->clone(osg::CopyOp::DEEP_COPY_ALL));
+    group = new osg::Group;
+    tx->addChild(geodeCopy);
+    geodeCopy->setNodeMask(viewer::NodeMask::NODE_MASK_ENTITY_MODEL);
+}
+
+int SetupADCIVCar( viewer::Viewer *viewer)
+{
+    int carModelID = 2;
+    Car *car_ = new Car;
+    // Higher speeds in lanes closer to reference lane
+    car_->speed_factor = 0.5 ;  // Speed vary between 0.5 to 1.0 times default speed
+    car_->road_id_init = 0;
+    car_->lane_id_init = 0;
+    car_->s_init = 0;
+ //   car_->pos = new roadmanager::Position(odrManager->GetRoadByIdx(r)->GetId(), lane->GetId(), s, 0);
+ //   car_->pos->SetHeadingRelative(lane->GetId() < 0 ? 0 : M_PI);
+ //   car_->heading_init = car_->pos->GetHRelative();
+
+    if ((car_->model = viewer->AddEntityModel(carModelsFiles_[carModelID], osg::Vec3(0.5, 0.5, 0.5),
+        viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0)) == 0)
+    {
+        return -1;
+    }
+    car_->id = 0;
+    if (first_car_in_focus == -1 )
+    {
+        first_car_in_focus = car_->id;
+    }
+    gADCIV_car = car_;
+    return 0;
+}
+
+int SetupCars(roadmanager::OpenDrive *odrManager, viewer::Viewer *viewer)
+{
+	if (density < 1E-10)
+	{
+		// Basically no scenario vehicles
+		return 0;
+	}
+
+//    for (int r = 0; r < 10; r++)
+	for (int r = 0; r < odrManager->GetNumOfRoads(); r++)
+	{
+		roadmanager::Road *road = odrManager->GetRoadByIdx(r);
+		double average_distance = 100.0 / density;
+
+		if (road->GetLength() > ROAD_MIN_LENGTH)
+		{
+			// Populate road lanes with vehicles at some random distances
+			for (double s = 10; s < road->GetLength() - average_distance; s += average_distance + 0.2 * average_distance * mt_rand() / mt_rand.max())
+			{
+				// Pick lane by random
+				int lane_idx = ((double)road->GetNumberOfDrivingLanes(s) * mt_rand()) / (mt_rand.max)();
+				roadmanager::Lane *lane = road->GetDrivingLaneByIdx(s, lane_idx);
+				if (lane == 0)
+				{
+					LOG("Failed locate driving lane %d at s %d", lane_idx, s);
+					continue;
+				}
+
+
+				if ((SIGN(lane->GetId()) < 0) && (road->GetLength() - s < 50) && (road->GetLink(roadmanager::LinkType::SUCCESSOR) == 0) ||
+					(SIGN(lane->GetId()) > 0) && (s < 50) && (road->GetLink(roadmanager::LinkType::PREDECESSOR) == 0))
+				{
+					// Skip vehicles too close to road end - and where connecting road is missing
+					continue;
+				}
+
+				// randomly choose model
+				int carModelID = (double(sizeof(carModelsFiles_) / sizeof(carModelsFiles_[0])) * mt_rand()) / (mt_rand.max)();
+				LOG("Adding car of model %d to road nr %d (road id %d s %.2f lane id %d), ", carModelID, r, road->GetId(), s, lane->GetId());
+
+                carModelID = 2;
+
+				Car *car_ = new Car;
+				// Higher speeds in lanes closer to reference lane
+				car_->speed_factor = 0.5 + 0.5 / abs(lane->GetId());  // Speed vary between 0.5 to 1.0 times default speed
+				car_->road_id_init = odrManager->GetRoadByIdx(r)->GetId();
+				car_->lane_id_init = lane->GetId();
+				car_->s_init = s;
+				car_->pos = new roadmanager::Position(odrManager->GetRoadByIdx(r)->GetId(), lane->GetId(), s, 0);
+				car_->pos->SetHeadingRelative(lane->GetId() < 0 ? 0 : M_PI);
+				car_->heading_init = car_->pos->GetHRelative();
+
+				if ((car_->model = viewer->AddEntityModel(carModelsFiles_[carModelID], osg::Vec3(0.5, 0.5, 0.5), 
+					viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0)) == 0)
+				{
+					return -1;
+				}
+				car_->id = cars.size();
+				cars.push_back(car_);
+				if (first_car_in_focus == -1 && lane->GetId() < 0)
+				{
+					first_car_in_focus = car_->id;
+				}
+
+			}
+		}
+	}
+
+	if (first_car_in_focus == -1)
+	{
+		first_car_in_focus = 0;
+	}
+
+	return 0;
+}
+
+int SetupCarsSpecial(roadmanager::OpenDrive* odrManager, viewer::Viewer* viewer)
+{
+	// Setup one single vehicle in a dedicated pos
+	Car* car_ = new Car;
+	
+	car_->speed_factor = 1.0;
+	car_->road_id_init = 1;
+	car_->lane_id_init = -1;
+	car_->s_init = 40;
+	car_->pos = new roadmanager::Position(car_->road_id_init, car_->lane_id_init, car_->s_init, 0);
+	car_->pos->SetHeadingRelative(car_->lane_id_init < 0 ? 0 : M_PI);
+	car_->heading_init = car_->pos->GetHRelative();
+
+	if ((car_->model = viewer->AddEntityModel(carModelsFiles_[0], osg::Vec3(0.5, 0.5, 0.5),
+		viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0)) == 0)
+	{
+		return -1;
+	}
+	car_->id = cars.size();
+	cars.push_back(car_);
+
+	first_car_in_focus = 0;
+
+	return 0;
+}
+
+
+void updateADCIVCar(Car * car)
+{
+
+    static float x=0;
+    static float y=0;
+    static float z=0;
+    static float head = M_PI/2.0;
+    static float pitch =0;
+    static float roll = 0;
+
+    if (car->model->txNode_ != 0)
+    {
+//        car->model->txNode_->setPosition(osg::Vec3(car->pos->GetX(), car->pos->GetY(), car->pos->GetZ()));
+
+//        car->model->quat_.makeRotate(
+//                    car->pos->GetR(), osg::Vec3(1, 0, 0),
+//                    car->pos->GetP(), osg::Vec3(0, 1, 0),
+//                    car->pos->GetH(), osg::Vec3(0, 0, 1));
+
+        y = y+ 0.1;
+        x = gfrel_x;
+        y = gfrel_y;
+        z = gfrel_z - gvehicleheight;
+        head = gvehicle_hdg;
+        car->model->txNode_->setPosition(osg::Vec3(x, y, z));
+
+        car->model->quat_.makeRotate(
+                    roll, osg::Vec3(1, 0, 0),
+                    pitch, osg::Vec3(0, 1, 0),
+                    head, osg::Vec3(0, 0, 1));
+
+        car->model->txNode_->setAttitude(car->model->quat_);
+    }
+
+}
+
+
+void updateCar(roadmanager::OpenDrive *odrManager, Car *car, double dt)
+{
+	double new_speed = car->pos->GetSpeedLimit() * car->speed_factor * global_speed_factor;
+	double ds = new_speed * dt; // right lane is < 0 in road dir;
+
+	if (car->pos->MoveAlongS(ds) != 0)
+	{
+		// Start from beginning of lane section - not initial s-position
+		roadmanager::LaneSection* ls = odrManager->GetRoadById(car->road_id_init)->GetLaneSectionByS(car->s_init);
+		double start_s = ls->GetS() + 5;
+		if (car->lane_id_init > 0)
+		{
+			start_s = ls->GetS() + ls->GetLength() - 5;
+		}
+		car->pos->SetLanePos(car->road_id_init, car->lane_id_init, start_s, 0);
+		car->pos->SetHeadingRelative(car->heading_init);
+	}
+
+	if (car->model->txNode_ != 0)
+	{
+		car->model->txNode_->setPosition(osg::Vec3(car->pos->GetX(), car->pos->GetY(), car->pos->GetZ()));
+
+		car->model->quat_.makeRotate(
+			car->pos->GetR(), osg::Vec3(1, 0, 0),
+			car->pos->GetP(), osg::Vec3(0, 1, 0),
+			car->pos->GetH(), osg::Vec3(0, 0, 1));
+
+		car->model->txNode_->setAttitude(car->model->quat_);
+	}
+}
+
+int main(int argc, char** argv)
+{
+	static char str_buf[128];
+	SE_Options opt;
+
+    argc = 3;
+    argv = new char*[3];
+    argv[0] = "testodrviewer";
+    argv[1] = "--odr";
+    argv[2] = "/home/yuchuli/map/models/y.xodr";
+
+
+    void * pa = iv::modulecomm::RegisterRecv("hcp2_gpsimu",Listengpsimu);
+    (void)pa;
+
+	// Use logger callback
+	Logger::Inst().SetCallback(log_callback);
+
+	mt_rand.seed((unsigned int)time(0));
+
+	std::vector<std::string> args;
+	for (int i = 0; i < argc; i++) args.push_back(argv[i]);
+
+	// use an ArgumentParser object to manage the program arguments.
+	opt.AddOption("odr", "OpenDRIVE filename", "odr_filename");
+	opt.AddOption("model", "3D Model filename", "model_filename");
+	opt.AddOption("density", "density (cars / 100 m)", "density");
+	opt.AddOption("speed_factor", "speed_factor <number>", "speed_factor");
+	opt.AddOption("osi_lines", "Show OSI road lines (toggle during simulation by press 'u') ");
+	opt.AddOption("osi_points", "Show OSI road points (toggle during simulation by press 'y') ");
+	opt.AddOption("road_features", "Show OpenDRIVE road features (toggle during simulation by press 'o') ");
+	opt.AddOption("path", "Search path prefix for assets, e.g. car and sign model files", "path");
+	opt.AddOption("logfile_path", "logfile path/filename, e.g. \"../esmini.log\" (default: log.txt)", "path");
+	opt.AddOption("disable_log", "Prevent logfile from being created");
+	opt.AddOption("help", "Show this help message");
+
+    if (argc < 2 || opt.GetOptionSet("help"))
+    {
+        opt.PrintUsage();
+        return -1;
+    }
+
+	opt.ParseArgs(&argc, argv);
+
+	std::string arg_str;
+
+	if (opt.GetOptionSet("disable_log"))
+	{
+		SE_Env::Inst().SetLogFilePath("");
+		printf("Disable logfile\n");
+	}
+	else if (opt.IsOptionArgumentSet("logfile_path"))
+	{
+		arg_str = opt.GetOptionArg("logfile_path");
+		SE_Env::Inst().SetLogFilePath(arg_str);
+		if (arg_str.empty())
+		{
+			printf("Custom logfile path empty, disable logfile\n");
+		}
+		else
+		{
+			printf("Custom logfile path: %s\n", arg_str.c_str());
+		}
+	}
+	Logger::Inst().OpenLogfile();
+
+	if ((arg_str = opt.GetOptionArg("path")) != "")
+	{
+		SE_Env::Inst().AddPath(arg_str);
+		LOG("Added path %s", arg_str.c_str());
+	}
+
+
+
+	std::string odrFilename = opt.GetOptionArg("odr");
+ //   odrFilename = "/home/yuchuli/map/models/mapxiali.xodr";
+	if (odrFilename.empty())
+	{
+		printf("Missing required argument --odr\n");
+		opt.PrintUsage();
+		return -1;
+	}
+
+
+
+	std::string modelFilename = opt.GetOptionArg("model");
+	
+	if (opt.GetOptionArg("density") != "")
+	{
+		density = strtod(opt.GetOptionArg("density"));
+	}
+	printf("density: %.2f\n", density);
+
+	if (opt.GetOptionArg("speed_factor") != "")
+	{
+		global_speed_factor = strtod(opt.GetOptionArg("speed_factor"));
+	}
+	printf("global speed factor: %.2f\n", global_speed_factor);
+
+	roadmanager::Position *lane_pos = new roadmanager::Position();
+	roadmanager::Position *track_pos = new roadmanager::Position();
+
+	try
+	{
+		if (!roadmanager::Position::LoadOpenDrive(odrFilename.c_str()))
+		{
+			printf("Failed to load ODR %s\n", odrFilename.c_str());
+			return -1;
+		}
+		roadmanager::OpenDrive *odrManager = roadmanager::Position::GetOpenDrive();
+
+		osg::ArgumentParser arguments(&argc, argv);
+		viewer::Viewer *viewer = new viewer::Viewer(
+			odrManager,
+			modelFilename.c_str(),
+			NULL,
+			argv[0],
+			arguments,
+			&opt);
+
+		viewer->SetWindowTitleFromArgs(args);
+		
+		if (opt.GetOptionSet("road_features"))
+		{
+			viewer->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_ODR_FEATURES);
+		}
+		else
+		{
+			viewer->ClearNodeMaskBits(viewer::NodeMask::NODE_MASK_ODR_FEATURES);
+		}
+
+		if (opt.GetOptionSet("osi_lines"))
+		{
+			viewer->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_OSI_LINES);
+		}
+
+		if (opt.GetOptionSet("osi_points"))
+		{
+			viewer->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_OSI_POINTS);
+		}
+
+		printf("osi_features: lines %s points %s \n",
+			viewer->GetNodeMaskBit(viewer::NodeMask::NODE_MASK_OSI_LINES) ? "on" : "off",
+			viewer->GetNodeMaskBit(viewer::NodeMask::NODE_MASK_OSI_POINTS) ? "on" : "off");
+
+         SetupADCIVCar(viewer);
+//        if (SetupCars(odrManager, viewer) == -1)
+//        {
+//            return 4;
+//        }
+
+
+		printf("%d cars added\n", (int)cars.size());
+		viewer->SetVehicleInFocus(first_car_in_focus);
+
+		__int64 now, lastTimeStamp = 0;
+
+		static bool first_time = true;
+
+		while (!viewer->osgViewer_->done())
+		{
+			// Get milliseconds since Jan 1 1970
+			now = SE_getSystemTime();
+			deltaSimTime = (now - lastTimeStamp) / 1000.0;  // step size in seconds
+			lastTimeStamp = now;
+			if (deltaSimTime > maxStepSize) // limit step size
+			{
+				deltaSimTime = maxStepSize;
+			}
+			else if (deltaSimTime < minStepSize)  // avoid CPU rush, sleep for a while
+			{
+				SE_sleep(now - lastTimeStamp);
+				deltaSimTime = minStepSize;
+			}
+
+			if (!(run_only_once && !first_time))
+			{
+                updateADCIVCar(gADCIV_car);
+                for (size_t i = 0; i < cars.size(); i++)
+                {
+                    updateCar(odrManager, cars[i], deltaSimTime);
+                }
+				first_time = false;
+			}
+
+            snprintf(str_buf, sizeof(str_buf), "(%6.2f,%6.2f,%6.2f,%6.2f) (%6.2fkm/h)", gfrel_x,
+                gfrel_y,gfrel_z,gvehicle_hdg,gfspeed);
+            viewer->SetInfoText(str_buf);
+			// Set info text
+			if (cars.size() > 0 && viewer->currentCarInFocus_ >= 0 && viewer->currentCarInFocus_ < cars.size())
+			{
+				Car* car = cars[viewer->currentCarInFocus_];
+				snprintf(str_buf, sizeof(str_buf), "entity[%d]: %.2fkm/h (%d, %d, %.2f, %.2f) / (%.2f, %.2f %.2f)", viewer->currentCarInFocus_,
+					3.6 * car->pos->GetSpeedLimit() * car->speed_factor * global_speed_factor, car->pos->GetTrackId(), car->pos->GetLaneId(),
+					fabs(car->pos->GetOffset()) < SMALL_NUMBER ? 0 : car->pos->GetOffset(), car->pos->GetS(), car->pos->GetX(), car->pos->GetY(), car->pos->GetH());
+				viewer->SetInfoText(str_buf);
+			}
+
+			// Step the simulation
+			viewer->osgViewer_->frame();
+		}
+		delete viewer;
+	}
+	catch (std::logic_error &e)
+	{
+		printf("%s\n", e.what());
+		return 2;
+	}
+	catch (std::runtime_error &e)
+	{
+		printf("%s\n", e.what());
+		return 3;
+	}
+
+	for (size_t i = 0; i < cars.size(); i++)
+	{
+		delete(cars[i]);
+	}
+	delete track_pos;
+	delete lane_pos;
+
+	return 0;
+}

+ 72 - 0
src/ui/ui_osgviewer/ui_osgviewer.pro

@@ -0,0 +1,72 @@
+QT -= gui
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+        ../../../thirdpartylib/esminilib/CommonMini.cpp \
+        ../../../thirdpartylib/esminilib/RoadManager.cpp \
+        ../../../thirdpartylib/esminilib/RubberbandManipulator.cpp \
+        ../../include/msgtype/gps.pb.cc \
+        ../../include/msgtype/gpsimu.pb.cc \
+        ../../include/msgtype/imu.pb.cc \
+        gnss_coordinate_convert.cpp \
+        main.cpp \
+        ../../../thirdpartylib/esminilib/odrSpiral.cpp \
+        ../../../thirdpartylib/esminilib/pugixml.cpp \
+        ../../../thirdpartylib/esminilib/roadgeom.cpp \
+        ../../../thirdpartylib/esminilib/vehicle.cpp \
+        viewer.cpp
+
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+
+INCLUDEPATH += /home/yuchuli/File/git/OpenSceneGraph/include
+
+INCLUDEPATH += /home/yuchuli/File/git/OpenSceneGraph/build/include
+
+INCLUDEPATH += $$PWD/../../../thirdpartylib/esminilib
+
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+!include(../../../include/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}
+
+!include(../../../include/ivboost.pri ) {
+    error( "Couldn't find the ivboost.pri file!" )
+}
+
+
+LIBS += -L/home/yuchuli/File/git/OpenSceneGraph/build/lib -losg -losgDB -losgFX \
+        -losgGA -losgViewer -losgSim -losgUtil -losgText
+
+
+LIBS += /home/yuchuli/File/git/OpenSceneGraph/build/lib/osgPlugins-3.7.0/osgdb_serializers_osg.so
+LIBS += /home/yuchuli/File/git/OpenSceneGraph/build/lib/osgPlugins-3.7.0/osgdb_osg.so
+LIBS += /home/yuchuli/File/git/OpenSceneGraph/build/lib/osgPlugins-3.7.0/osgdb_serializers_osgsim.so
+LIBS += /home/yuchuli/File/git/OpenSceneGraph/build/lib/osgPlugins-3.7.0/osgdb_jpeg.so
+
+HEADERS += \
+    ../../include/msgtype/gps.pb.h \
+    ../../include/msgtype/gpsimu.pb.h \
+    ../../include/msgtype/imu.pb.h \
+    gnss_coordinate_convert.h

+ 2155 - 0
src/ui/ui_osgviewer/viewer.cpp

@@ -0,0 +1,2155 @@
+/* 
+ * esmini - Environment Simulator Minimalistic 
+ * https://github.com/esmini/esmini
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this
+ * file, You can obtain one at https://mozilla.org/MPL/2.0/.
+ * 
+ * Copyright (c) partners of Simulation Scenarios
+ * https://sites.google.com/view/simulationscenarios
+ */
+
+#include "viewer.hpp"
+
+#include <osgDB/ReadFile>
+#include <osg/ComputeBoundsVisitor>
+#include <osg/LineWidth>
+#include <osg/Point>
+#include <osg/BlendFunc>
+#include <osg/BlendColor>
+#include <osg/Geode> 
+#include <osg/Group> 
+#include <osg/ShapeDrawable>
+#include <osg/CullFace>
+#include <osgGA/StateSetManipulator>
+#include <osgGA/TrackballManipulator>
+#include <osgGA/KeySwitchMatrixManipulator>
+#include <osgGA/FlightManipulator>
+#include <osgGA/DriveManipulator>
+#include <osgGA/TerrainManipulator>
+#include <osgGA/SphericalManipulator>
+#include <osgViewer/ViewerEventHandlers>
+#include <osgDB/Registry>
+#include <osgShadow/StandardShadowMap>
+#include <osgShadow/ShadowMap>
+#include <osgShadow/ShadowedScene>
+#include <osgUtil/SmoothingVisitor>
+#include <osgUtil/Tessellator> // to tessellate multiple contours
+
+#include "CommonMini.hpp"
+
+#define SHADOW_SCALE 1.20
+#define SHADOW_MODEL_FILEPATH "shadow_face.osgb"  
+#define ARROW_MODEL_FILEPATH "arrow.osgb"
+#define LOD_DIST 3000
+#define LOD_SCALE_DEFAULT 1.0
+#define DEFAULT_AA_MULTISAMPLES 4
+#define OSI_LINE_WIDTH 2.0f
+
+double color_green[3] = { 0.25, 0.6, 0.3 };
+double color_gray[3] = { 0.7, 0.7, 0.7 };
+double color_dark_gray[3] = { 0.5, 0.5, 0.5 };
+double color_red[3] = { 0.73, 0.26, 0.26 };
+double color_blue[3] = { 0.25, 0.38, 0.7 };
+double color_yellow[3] = { 0.75, 0.7, 0.4 };
+double color_white[3] = { 0.80, 0.80, 0.79 };
+
+//USE_OSGPLUGIN(fbx)
+//USE_OSGPLUGIN(obj)
+USE_OSGPLUGIN(osg2)
+USE_OSGPLUGIN(jpeg)
+USE_SERIALIZER_WRAPPER_LIBRARY(osg)
+USE_SERIALIZER_WRAPPER_LIBRARY(osgSim)
+USE_COMPRESSOR_WRAPPER(ZLibCompressor)
+USE_GRAPHICSWINDOW()
+
+using namespace viewer;
+
+static osg::ref_ptr<osgShadow::ShadowedScene> shadowedScene;
+
+// Derive a class from NodeVisitor to find a node with a  specific name.
+class FindNamedNode : public osg::NodeVisitor
+{
+public:
+	FindNamedNode(const std::string& name)
+		: osg::NodeVisitor( // Traverse all children.
+			osg::NodeVisitor::TRAVERSE_ALL_CHILDREN),
+		_name(name) {}
+
+	// This method gets called for every node in the scene graph. Check each node 
+	// to see if its name matches out target. If so, save the node's address.
+	virtual void apply(osg::Group& node)
+	{
+		if (node.getName() == _name )
+		{
+			_node = &node;
+		}
+		else
+		{
+
+			// Keep traversing the rest of the scene graph.
+			traverse(node);
+		}
+	}
+
+	osg::Node* getNode() { return _node.get(); }
+
+protected:
+	std::string _name;
+	osg::ref_ptr<osg::Group> _node;
+};
+
+Line::Line(double x0, double y0, double z0, double x1, double y1, double z1, double r, double g, double b)
+{
+	line_vertex_data_ = new osg::Vec3Array;
+	line_vertex_data_->push_back(osg::Vec3d(x0, y0, z0));
+	line_vertex_data_->push_back(osg::Vec3d(x1, y1, z1));
+
+	osg::ref_ptr<osg::Group> group = new osg::Group;
+	line_ = new osg::Geometry();
+
+	line_->setVertexArray(line_vertex_data_.get());
+	line_->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP, 0, 2));
+
+	line_->getOrCreateStateSet()->setAttributeAndModes(new osg::LineWidth(2), osg::StateAttribute::ON);
+	line_->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+	osg::ref_ptr<osg::Vec4Array> color_ = new osg::Vec4Array;
+	color_->push_back(osg::Vec4(r, g, b, 1.0));
+	line_->setColorArray(color_.get());
+	line_->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
+}
+
+void Line::SetPoints(double x0, double y0, double z0, double x1, double y1, double z1)
+{
+	line_vertex_data_->clear();
+	line_vertex_data_->push_back(osg::Vec3d(x0, y0, z0));
+	line_vertex_data_->push_back(osg::Vec3d(x1, y1, z1));
+	line_->dirtyGLObjects();
+	line_->dirtyBound();
+	line_vertex_data_->dirty();
+}
+
+SensorViewFrustum::SensorViewFrustum(ObjectSensor *sensor, osg::Group *parent)
+{
+	sensor_ = sensor;
+	txNode_ = new osg::PositionAttitudeTransform;
+	txNode_->setNodeMask(NodeMask::NODE_MASK_OBJECT_SENSORS);
+	parent->addChild(txNode_);
+
+	// Create geometry
+	int numSegments = 16 * sensor_->fovH_ / M_PI;
+	double angleDelta = sensor_->fovH_ / numSegments;
+	double angle = -sensor_->fovH_ / 2.0;
+	double fovV_rate = 0.2;
+
+	line_group_ = new osg::Group;
+	for (size_t i = 0; i < sensor_->maxObj_; i++)
+	{
+		Line *line = new Line(0, 0, 0, 1, 0, 0, 0.8, 0.8, 0.8);
+		line_group_->addChild(line->line_);
+		lines_.push_back(line);
+	}
+
+	txNode_->addChild(line_group_);
+
+	osg::ref_ptr<osg::Vec3Array> vertices = new osg::Vec3Array(4 * (numSegments+1));
+	osg::ref_ptr<osg::DrawElementsUInt> indices = new osg::DrawElementsUInt(GL_QUADS, 2 * 4 + 4 * 4 * numSegments);
+
+	osg::ref_ptr<osg::DrawElementsUInt> indicesC0 = new osg::DrawElementsUInt(GL_LINE_STRIP, numSegments+1);
+	osg::ref_ptr<osg::DrawElementsUInt> indicesC1 = new osg::DrawElementsUInt(GL_LINE_STRIP, numSegments+1);
+	osg::ref_ptr<osg::DrawElementsUInt> indicesC2 = new osg::DrawElementsUInt(GL_LINE_STRIP, numSegments+1);
+	osg::ref_ptr<osg::DrawElementsUInt> indicesC3 = new osg::DrawElementsUInt(GL_LINE_STRIP, numSegments+1);
+	osg::ref_ptr<osg::DrawElementsUInt> indicesC4 = new osg::DrawElementsUInt(GL_LINE_LOOP, 4);
+	osg::ref_ptr<osg::DrawElementsUInt> indicesC5 = new osg::DrawElementsUInt(GL_LINE_LOOP, 4);
+
+	size_t i;
+	unsigned int idx = 0;
+	unsigned int idxC = 0;
+
+	for (i = 0; i < numSegments+1; ++i, angle += angleDelta)
+	{
+		float x = cosf(angle);
+		float y = sinf(angle);
+
+		(*vertices)[i * 4 + 0].set(sensor_->near_ * x, sensor_->near_ * y, -sensor_->near_ * fovV_rate);
+		(*vertices)[i * 4 + 3].set(sensor_->far_ * x, sensor_->far_ * y, -sensor_->far_ * fovV_rate);
+		(*vertices)[i * 4 + 2].set(sensor_->far_ * x, sensor_->far_ * y, sensor_->far_ * fovV_rate);
+		(*vertices)[i * 4 + 1].set(sensor_->near_ * x, sensor_->near_ * y, sensor_->near_ * fovV_rate);
+
+		if (i > 0)
+		{
+			// Bottom face
+			(*indices)[idx++] = (i - 1) * 4 + 0;
+			(*indices)[idx++] = (i - 1) * 4 + 1;
+			(*indices)[idx++] = (i - 0) * 4 + 1;
+			(*indices)[idx++] = (i - 0) * 4 + 0;
+
+			// Top face
+			(*indices)[idx++] = (i - 1) * 4 + 3;
+			(*indices)[idx++] = (i - 0) * 4 + 3;
+			(*indices)[idx++] = (i - 0) * 4 + 2;
+			(*indices)[idx++] = (i - 1) * 4 + 2;
+
+			// Side facing host entity
+			(*indices)[idx++] = (i - 1) * 4 + 0;
+			(*indices)[idx++] = (i - 0) * 4 + 0;
+			(*indices)[idx++] = (i - 0) * 4 + 3;
+			(*indices)[idx++] = (i - 1) * 4 + 3;
+
+			// Side facing away from host entity
+			(*indices)[idx++] = (i - 1) * 4 + 1;
+			(*indices)[idx++] = (i - 1) * 4 + 2;
+			(*indices)[idx++] = (i - 0) * 4 + 2;
+			(*indices)[idx++] = (i - 0) * 4 + 1;
+		}
+		// Countour
+		(*indicesC0)[idxC] = i * 4 + 0;
+		(*indicesC1)[idxC] = i * 4 + 1;
+		(*indicesC2)[idxC] = i * 4 + 2;
+		(*indicesC3)[idxC++] = i * 4 + 3;
+	}
+
+	(*indicesC4)[0] = (*indices)[idx++] = 0;
+	(*indicesC4)[1] = (*indices)[idx++] = 3;
+	(*indicesC4)[2] = (*indices)[idx++] = 2;
+	(*indicesC4)[3] = (*indices)[idx++] = 1;
+			 	   
+	(*indicesC5)[0] = (*indices)[idx++] = (i - 1) * 4 + 0;
+	(*indicesC5)[1] = (*indices)[idx++] = (i - 1) * 4 + 1;
+	(*indicesC5)[2] = (*indices)[idx++] = (i - 1) * 4 + 2;
+	(*indicesC5)[3] = (*indices)[idx++] = (i - 1) * 4 + 3;
+
+	const osg::Vec4 normalColor(0.8f, 0.7f, 0.6f, 1.0f);
+	osg::ref_ptr<osg::Vec4Array> colors = new osg::Vec4Array(1);
+	(*colors)[0] = normalColor;
+
+	osg::ref_ptr<osg::Geometry> geom = new osg::Geometry;
+	osg::ref_ptr<osg::Geometry> geom2 = new osg::Geometry;
+	geom->setDataVariance(osg::Object::STATIC);
+	geom->setUseDisplayList(true);
+	geom->setUseVertexBufferObjects(true);
+	geom->setVertexArray(vertices.get());
+
+	geom2->setUseDisplayList(true);
+	geom2->setUseVertexBufferObjects(true);
+	geom2->setVertexArray(vertices.get());
+
+	geom->addPrimitiveSet(indices.get());
+	geom2->addPrimitiveSet(indicesC0.get());
+	geom2->addPrimitiveSet(indicesC1.get());
+	geom2->addPrimitiveSet(indicesC2.get());
+	geom2->addPrimitiveSet(indicesC3.get());
+	geom2->addPrimitiveSet(indicesC4.get());
+	geom2->addPrimitiveSet(indicesC5.get());
+	geom2->setColorArray(colors.get());
+	geom2->setColorBinding(osg::Geometry::BIND_OVERALL);
+
+	osgUtil::SmoothingVisitor::smooth(*geom, 0.5);
+	osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+	geode->addDrawable(geom.release());
+	osg::ref_ptr<osg::Material> material = new osg::Material;
+	material->setDiffuse(osg::Material::FRONT, osg::Vec4(1.0, 1.0, 1.0, 0.2));
+	material->setAmbient(osg::Material::FRONT, osg::Vec4(1.0, 1.0, 1.0, 0.2));
+
+	osg::ref_ptr<osg::StateSet> stateset = geode->getOrCreateStateSet(); // Get the StateSet of the group
+	stateset->setAttribute(material.get()); // Set Material 
+	
+	stateset->setMode(GL_BLEND, osg::StateAttribute::ON);
+	stateset->setAttributeAndModes(new osg::BlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA));
+	stateset->setRenderingHint(osg::StateSet::TRANSPARENT_BIN);
+	osg::ref_ptr<osg::CullFace> cull = new osg::CullFace();
+	cull->setMode(osg::CullFace::BACK);
+	stateset->setAttributeAndModes(cull, osg::StateAttribute::ON);
+
+	// Draw only wireframe to 
+	osg::ref_ptr<osg::PolygonMode> polygonMode = new osg::PolygonMode;
+	polygonMode->setMode(osg::PolygonMode::FRONT_AND_BACK, osg::PolygonMode::LINE);
+	stateset->setAttributeAndModes(polygonMode, osg::StateAttribute::OVERRIDE | osg::StateAttribute::ON);
+
+	osg::ref_ptr<osg::Geode> geode2 = new osg::Geode;
+	geom2->getOrCreateStateSet()->setAttribute(new osg::LineWidth(1.0f));
+	geom2->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+	geode2->addDrawable(geom2.release());
+
+
+	txNode_->addChild(geode);
+	txNode_->addChild(geode2);
+	txNode_->setPosition(osg::Vec3(sensor_->pos_.x, sensor_->pos_.y, sensor_->pos_.z));
+	txNode_->setAttitude(osg::Quat(sensor_->pos_.h, osg::Vec3(0, 0, 1)));
+}
+
+SensorViewFrustum::~SensorViewFrustum()
+{
+	for (size_t i = 0; i < lines_.size(); i++)
+	{
+		delete lines_[i];
+	}
+	lines_.clear();
+}
+
+void SensorViewFrustum::Update()
+{
+	// Visualize hits by a "line of sight"
+	for (size_t i = 0; i < sensor_->nObj_; i++)
+	{
+		lines_[i]->SetPoints(0, 0, 0, sensor_->hitList_[i].x_, sensor_->hitList_[i].y_, sensor_->hitList_[i].z_);
+	}
+
+	// Reset additional lines possibly previously in use
+	for (size_t i = sensor_->nObj_; i < sensor_->maxObj_; i++)
+	{
+		lines_[i]->SetPoints(0, 0, 0, 0, 0, 0);
+	}
+}
+
+void VisibilityCallback::operator()(osg::Node* sa, osg::NodeVisitor* nv)
+{
+	if (object_->CheckDirtyBits(scenarioengine::Object::DirtyBit::VISIBILITY))
+	{
+		if (object_->visibilityMask_ & scenarioengine::Object::Visibility::GRAPHICS)
+		{
+			entity_->txNode_->getChild(0)->setNodeMask(NodeMask::NODE_MASK_ENTITY_MODEL);
+			if (object_->visibilityMask_ & scenarioengine::Object::Visibility::SENSORS)
+			{
+				entity_->SetTransparency(0.0);
+			}
+			else
+			{
+				entity_->SetTransparency(0.6);
+			}
+		}
+		else
+		{
+			// Must set 0-mask on child node, otherwise it will not be traversed...
+			entity_->txNode_->getChild(0)->setNodeMask(NodeMask::NODE_MASK_NONE);
+		}
+	}
+	object_->ClearDirtyBits(scenarioengine::Object::DirtyBit::VISIBILITY);
+
+}
+
+void AlphaFadingCallback::operator()(osg::StateAttribute* sa, osg::NodeVisitor*)
+{
+	osg::Material* material = static_cast<osg::Material*>(sa);
+	if (material)
+	{
+		double age = viewer_->elapsedTime() - born_time_stamp_;
+		double dt = viewer_->elapsedTime() - time_stamp_;
+		time_stamp_ = viewer_->elapsedTime();
+		if (age > TRAIL_DOT_LIFE_SPAN)
+		{
+			_motion->update(dt);  
+		}
+		color_[3] = 1 - _motion->getValue();
+		material->setDiffuse(osg::Material::FRONT_AND_BACK, color_);
+		material->setAmbient(osg::Material::FRONT_AND_BACK, color_);
+	}
+}
+
+TrailDot::TrailDot(double x, double y, double z, double heading, 
+	osgViewer::Viewer *viewer, osg::Group *parent, osg::ref_ptr<osg::Node> dot_node, osg::Vec4 trail_color)
+{
+	double dot_radius = 0.8;
+	osg::ref_ptr<osg::Node> new_node;
+
+	dot_ = new osg::PositionAttitudeTransform;
+	dot_->setPosition(osg::Vec3(x, y, z));
+	dot_->setScale(osg::Vec3(dot_radius, dot_radius, dot_radius));
+	dot_->setAttitude(osg::Quat(heading, osg::Vec3(0, 0, 1)));
+
+	if (dot_node == 0)
+	{
+		osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+		geode->addDrawable(new osg::ShapeDrawable(new osg::Box()));
+		new_node = geode;
+	}
+	else
+	{
+		// Clone into a unique object for unique material and alpha fading
+		new_node = dynamic_cast<osg::Node*>(dot_node->clone(osg::CopyOp()));
+	}
+	
+	dot_->addChild(new_node);
+
+	material_ = new osg::Material;
+	material_->setDiffuse(osg::Material::FRONT_AND_BACK, trail_color);
+	material_->setAmbient(osg::Material::FRONT_AND_BACK, trail_color);
+	fade_callback_ = new AlphaFadingCallback(viewer, trail_color);
+	material_->setUpdateCallback(fade_callback_);
+
+	new_node->getOrCreateStateSet()->setAttributeAndModes(material_.get());
+	osg::ref_ptr<osg::StateSet> stateset = new_node->getOrCreateStateSet(); // Get the StateSet of the group
+	stateset->setAttribute(material_.get()); // Set Material 
+	stateset->setAttributeAndModes(new osg::BlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA));
+	stateset->setRenderingHint(osg::StateSet::TRANSPARENT_BIN);
+	
+	dot_->setNodeMask(NodeMask::NODE_MASK_TRAILS);
+
+	parent->addChild(dot_);
+}
+
+static osg::ref_ptr<osg::Node> CreateDotGeometry()
+{
+	double height = 0.17;
+	osg::ref_ptr<osg::Vec3Array> vertices = new osg::Vec3Array(6);
+	osg::ref_ptr<osg::DrawElementsUInt> indices1 = new osg::DrawElementsUInt(GL_QUADS, 3 * 4);
+	osg::ref_ptr<osg::DrawElementsUInt> indices2 = new osg::DrawElementsUInt(GL_TRIANGLES, 3);
+	int idx = 0;
+
+	(*vertices)[idx++].set(0.0, -0.5, 0.0);
+	(*vertices)[idx++].set(0.87, 0.0, 0.0);
+	(*vertices)[idx++].set(0.0, 0.5, 0.0);
+	(*vertices)[idx++].set(0.0, -0.5, height);
+	(*vertices)[idx++].set(0.87, 0.0, height);
+	(*vertices)[idx++].set(0.0, 0.5, height);
+
+	// sides
+	idx = 0;
+	(*indices1)[idx++] = 0;
+	(*indices1)[idx++] = 1;
+	(*indices1)[idx++] = 4;
+	(*indices1)[idx++] = 3;
+
+	(*indices1)[idx++] = 2;
+	(*indices1)[idx++] = 5;
+	(*indices1)[idx++] = 4;
+	(*indices1)[idx++] = 1;
+
+	(*indices1)[idx++] = 0;
+	(*indices1)[idx++] = 3;
+	(*indices1)[idx++] = 5;
+	(*indices1)[idx++] = 2;
+
+	// Top face
+	idx = 0;
+	(*indices2)[idx++] = 3;
+	(*indices2)[idx++] = 4;
+	(*indices2)[idx++] = 5;
+
+	osg::ref_ptr<osg::Geometry> geom = new osg::Geometry;
+	geom->setDataVariance(osg::Object::DYNAMIC);
+	geom->setUseDisplayList(false);
+	geom->setUseVertexBufferObjects(true);
+	geom->setVertexArray(vertices.get());
+	geom->addPrimitiveSet(indices1.get());
+	geom->addPrimitiveSet(indices2.get());
+	osgUtil::SmoothingVisitor::smooth(*geom, 0.5);
+	osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+	geode->addDrawable(geom.release());
+
+	return geode;
+}
+
+void TrailDot::Reset(double x, double y, double z, double heading)
+{
+	dot_->setPosition(osg::Vec3(x, y, z));
+
+	dot_->setAttitude(osg::Quat(
+		0, osg::Vec3(1, 0, 0),       // Roll
+		0, osg::Vec3(0, 1, 0),       // Pitch
+		heading, osg::Vec3(0, 0, 1)) // Heading
+	); 
+
+	fade_callback_->Reset();
+}
+
+void Trail::AddDot(double x, double y, double z, double heading)
+{
+	if (n_dots_ < TRAIL_MAX_DOTS)
+	{
+		dot_[current_] = new TrailDot(x, y, z, heading, viewer_, parent_, dot_node_, color_);
+		n_dots_++;
+	}
+	else
+	{
+		dot_[current_]->Reset(x, y, z, heading);
+	}
+
+	if (++current_ >= TRAIL_MAX_DOTS)
+	{
+		current_ = 0;
+	}
+}
+
+Trail::~Trail()
+{
+	for (size_t i = 0; i < n_dots_; i++)
+	{
+		delete (dot_[i]);
+	}
+}
+
+osg::ref_ptr<osg::PositionAttitudeTransform> CarModel::AddWheel(osg::ref_ptr<osg::Node> carNode, const char *wheelName)
+{
+	osg::ref_ptr<osg::PositionAttitudeTransform> tx_node = 0;
+
+	// Find wheel node
+	FindNamedNode fnn(wheelName);
+	carNode->accept(fnn);	
+	
+	// Assume wheel is a tranformation node
+	osg::MatrixTransform *node = dynamic_cast<osg::MatrixTransform*>(fnn.getNode());
+
+	if (node != NULL)
+	{
+		tx_node = new osg::PositionAttitudeTransform;
+		// We found the wheel. Put it under a useful transform node
+		tx_node->addChild(node);
+
+		// reset pivot point
+		osg::Vec3d pos = node->getMatrix().getTrans();
+		tx_node->setPivotPoint(pos);
+		tx_node->setPosition(pos);
+
+		osg::ref_ptr<osg::Group> parent = node->getParent(0);  // assume the wheel node only belongs to one vehicle
+		parent->removeChild(node);
+		parent->addChild(tx_node);
+
+		wheel_.push_back(tx_node);
+	}
+
+	return tx_node;
+}
+
+EntityModel::EntityModel(osgViewer::Viewer *viewer, osg::ref_ptr<osg::Group> group, osg::ref_ptr<osg::Group> parent, 
+	osg::ref_ptr<osg::Group> trail_parent, osg::ref_ptr<osg::Node> dot_node, osg::Vec3 trail_color,std::string name)
+{
+	if (!group)
+	{
+		return;
+	}
+	name_ = name;
+	group_ = group;
+
+	// Add LevelOfDetail node
+	lod_ = new osg::LOD();
+	lod_->addChild(group_);
+	lod_->setRange(0, 0, LOD_DIST);
+	lod_->setName(name);
+
+	// Add transform node
+	txNode_ = new osg::PositionAttitudeTransform();
+	txNode_->addChild(lod_);
+	txNode_->setName(name);
+	parent->addChild(txNode_);
+
+	// Find boundingbox
+	bb_ = 0;
+	for (int i = 0; i < (int)group->getNumChildren(); i++)
+	{
+		if (group->getChild(i)->getName() == "BoundingBox")
+		{
+			bb_ = (osg::Group*)group->getChild(i);
+			break;
+		}
+	}
+
+	viewer_ = viewer;
+	state_set_ = 0;
+	blend_color_ = 0;
+
+	// Extract boundingbox of car to calculate size and center
+	osg::ComputeBoundsVisitor cbv;
+	txNode_->accept(cbv);
+	osg::BoundingBox boundingBox = cbv.getBoundingBox();
+	const osg::MatrixList& m = txNode_->getWorldMatrices();
+	osg::Vec3 minV = boundingBox._min * m.front();
+	osg::Vec3 maxV = boundingBox._max * m.front();
+
+	size_x = maxV.x() - minV.x();
+	size_y = maxV.y() - minV.y();
+	center_x = (maxV.x() + minV.x()) / 2;
+	center_y = (maxV.y() + minV.y()) / 2;
+	
+	// Prepare trail of dots
+	trail_ = new Trail(trail_parent, viewer, dot_node, trail_color);
+}
+
+CarModel::CarModel(osgViewer::Viewer* viewer, osg::ref_ptr<osg::Group> group, osg::ref_ptr<osg::Group> parent,
+	osg::ref_ptr<osg::Group> trail_parent, osg::ref_ptr<osg::Node> dot_node, osg::Vec3 trail_color, std::string name):
+	EntityModel(viewer, group, parent, trail_parent, dot_node, trail_color, name)
+{
+	steering_sensor_ = 0;
+	road_sensor_ = 0;
+	lane_sensor_ = 0;
+	trail_sensor_ = 0;
+
+	wheel_angle_ = 0;
+	wheel_rot_ = 0;
+
+	osg::ref_ptr<osg::Group> retval[4];
+	osg::ref_ptr<osg::Node> car_node = txNode_->getChild(0);
+	retval[0] = AddWheel(car_node, "wheel_fl");
+	retval[1] = AddWheel(car_node, "wheel_fr");
+	retval[2] = AddWheel(car_node, "wheel_rr");
+	retval[3] = AddWheel(car_node, "wheel_rl");
+	if (!(retval[0] || retval[1] || retval[2] || retval[3]))
+	{
+		LOG("No wheel nodes in model %s. No problem, wheels will just not appear to roll or steer", car_node->getName().c_str());
+	}
+	else
+	{
+		if (!retval[0])
+		{
+			LOG("Missing wheel node %s in vehicle model %s - ignoring", "wheel_fl", car_node->getName().c_str());
+		}
+		if (!retval[1])
+		{
+			LOG("Missing wheel node %s in vehicle model %s - ignoring", "wheel_fr", car_node->getName().c_str());
+		}
+		if (!retval[2])
+		{
+			LOG("Missing wheel node %s in vehicle model %s - ignoring", "wheel_rr", car_node->getName().c_str());
+		}
+		if (!retval[3])
+		{
+			LOG("Missing wheel node %s in vehicle model %s - ignoring", "wheel_rl", car_node->getName().c_str());
+		}
+	}
+}
+
+CarModel ::~CarModel()
+{
+	wheel_.clear();
+	delete trail_;
+}
+
+void EntityModel::SetPosition(double x, double y, double z)
+{
+	txNode_->setPosition(osg::Vec3(x, y, z));
+}
+
+void EntityModel::SetRotation(double h, double p, double r)
+{
+	quat_.makeRotate(
+		r, osg::Vec3(1, 0, 0), // Roll
+		p, osg::Vec3(0, 1, 0), // Pitch
+		h, osg::Vec3(0, 0, 1)); // Heading
+	txNode_->setAttitude(quat_);
+}
+
+void CarModel::UpdateWheels(double wheel_angle, double wheel_rotation)
+{
+	// Update wheel angles and rotation for front wheels
+	wheel_angle_ = wheel_angle;
+	wheel_rot_ = wheel_rotation;
+	
+	osg::Quat quat;
+	quat.makeRotate(
+		0, osg::Vec3(1, 0, 0), // Roll
+		wheel_rotation, osg::Vec3(0, 1, 0), // Pitch
+		wheel_angle, osg::Vec3(0, 0, 1)); // Heading
+
+	if (wheel_.size() < 4)
+	{
+		// Wheels not available
+		return;
+	}
+
+	wheel_[0]->setAttitude(quat);
+	wheel_[1]->setAttitude(quat);
+	
+	// Update rotation for rear wheels
+	quat.makeRotate(
+		0, osg::Vec3(1, 0, 0), // Roll
+		wheel_rotation, osg::Vec3(0, 1, 0), // Pitch
+		0, osg::Vec3(0, 0, 1)); // Heading
+	wheel_[2]->setAttitude(quat);
+	wheel_[3]->setAttitude(quat);
+}
+
+void CarModel::UpdateWheelsDelta(double wheel_angle, double wheel_rotation_delta)
+{
+	UpdateWheels(wheel_angle, wheel_rot_ + wheel_rotation_delta);
+}
+
+void EntityModel::SetTransparency(double factor)
+{
+	if (factor < 0 || factor > 1)
+	{
+		LOG("Clamping transparency factor %.2f to [0:1]", factor);
+		factor = CLAMP(factor, 0, 1); 
+	}
+	blend_color_->setConstantColor(osg::Vec4(1, 1, 1, 1-factor));
+}
+
+Viewer::Viewer(roadmanager::OpenDrive* odrManager, const char* modelFilename, const char* scenarioFilename, const char* exe_path, osg::ArgumentParser arguments, SE_Options* opt)
+{
+	odrManager_ = odrManager;
+	bool clear_color;
+	std::string arg_str;
+	osgViewer_ = 0;
+
+	if(scenarioFilename != NULL)
+	{ 
+		SE_Env::Inst().AddPath(DirNameOf(scenarioFilename));
+	}
+
+	if (odrManager != NULL)
+	{
+		SE_Env::Inst().AddPath(DirNameOf(odrManager->GetOpenDriveFilename()));
+	}
+
+	if (modelFilename != NULL)
+	{
+		SE_Env::Inst().AddPath(DirNameOf(modelFilename));
+	}
+
+	lodScale_ = LOD_SCALE_DEFAULT;
+	currentCarInFocus_ = 0;
+	keyUp_ = false;
+	keyDown_ = false;
+	keyLeft_ = false;
+	keyRight_ = false;
+	quit_request_ = false;
+	showInfoText = true;  // show info text HUD per default
+	camMode_ = osgGA::RubberbandManipulator::RB_MODE_ORBIT;
+	shadow_node_ = NULL;
+	environment_ = NULL;
+	roadGeom = NULL;
+
+	int aa_mode = DEFAULT_AA_MULTISAMPLES;  
+	if (opt && (arg_str = opt->GetOptionArg("aa_mode")) != "")
+	{
+		aa_mode = atoi(arg_str.c_str());
+	}
+	LOG("Anti-Aliasing number of subsamples: %d", aa_mode);
+	osg::DisplaySettings::instance()->setNumMultiSamples(aa_mode);
+
+	arguments.getApplicationUsage()->addCommandLineOption("--lodScale <number>", "LOD Scale");
+	arguments.read("--lodScale", lodScale_);
+
+	clear_color = (arguments.find("--clear-color") != -1);
+
+	// Store arguments in case we need to create a second viewer if the first fails
+	int argc = arguments.argc() + 2;  // make room for screen argument
+	char **argv = (char**)malloc(argc * sizeof(char*));
+	for (int i = 0; i < argc; i++)
+	{
+		argv[i] = (char*)malloc(strlen(arguments.argv()[i]) + 1);  // +1 to include null termination
+		strncpy(argv[i], arguments.argv()[i], strlen(arguments.argv()[i]) + 1);
+	}
+
+	osgViewer_ = new osgViewer::Viewer(arguments);
+
+	// Check if the viewer has been created correctly - window created is a indication
+	osgViewer::ViewerBase::Windows wins;
+	osgViewer_->getWindows(wins);
+	if (wins.size() == 0)
+	{
+		// Viewer failed to create window. Probably Anti Aliasing is not supported on executing platform.
+		// Make another attempt without AA
+		LOG("Viewer failure. Probably requested level of Anti Aliasing (%d multisamples) is not supported - try a lower number. Making another attempt without Anti-Alias and single screen.", aa_mode);
+		osg::DisplaySettings::instance()->setNumMultiSamples(0);
+		delete osgViewer_;
+		osg::ArgumentParser args2(&argc, argv);
+		// force single screen
+		strncpy(argv[argc - 2], "--screen", strlen("--screen") + 1);
+		strncpy(argv[argc - 1], "0", strlen("0") + 1);
+
+		osgViewer_ = new osgViewer::Viewer(args2);
+		osgViewer_->getWindows(wins);
+		if (wins.size() == 0)
+		{
+			LOG("Failed second attempt opening a viewer window. Give up.");
+			delete osgViewer_;
+			for (int i = 0; i < argc; i++)
+			{
+				free(argv[i]);
+			}
+			return;
+		}
+	}
+	else
+	{
+		for (int i = 0; i < argc; i++)
+		{
+			free(argv[i]);
+		}
+		free(argv);
+	}
+
+	// Create 3D geometry for trail dots
+	dot_node_ = CreateDotGeometry();
+
+	// set the scene to render
+	rootnode_ = new osg::MatrixTransform;
+	
+#if 0
+	// Setup shadows
+	const int CastsShadowTraversalMask = 0x2;
+	LOG("1");
+	shadowedScene = new osgShadow::ShadowedScene;
+	osgShadow::ShadowSettings* settings = shadowedScene->getShadowSettings();
+	LOG("2");
+	settings->setReceivesShadowTraversalMask(CastsShadowTraversalMask);
+//	shadowedScene->setCastsShadowTraversalMask(CastsShadowTraversalMask);
+	osg::ref_ptr<osgShadow::ShadowMap> st = new osgShadow::ShadowMap;
+//	osg::ref_ptr<osgShadow::StandardShadowMap> st = new osgShadow::StandardShadowMap;
+	int mapres = 1024;
+	LOG("3");
+	st->setTextureSize(osg::Vec2s(mapres, mapres));
+	shadowedScene->setShadowTechnique(st.get());
+	shadowedScene->addChild(rootnode_);
+	LOG("4");
+#endif
+
+	envTx_ = new osg::PositionAttitudeTransform;
+	envTx_->setPosition(osg::Vec3(0, 0, 0));
+	envTx_->setScale(osg::Vec3(1, 1, 1));
+	envTx_->setAttitude(osg::Quat(0, 0, 0, 1));
+	envTx_->setNodeMask(NodeMask::NODE_MASK_ENV_MODEL);
+	rootnode_->addChild(envTx_);
+
+	ClearNodeMaskBits(NodeMask::NODE_MASK_TRAILS); // hide trails per default
+	ClearNodeMaskBits(NodeMask::NODE_MASK_OSI_LINES);
+	ClearNodeMaskBits(NodeMask::NODE_MASK_OSI_POINTS);
+	ClearNodeMaskBits(NodeMask::NODE_MASK_OBJECT_SENSORS);
+	ClearNodeMaskBits(NodeMask::NODE_MASK_ODR_FEATURES);
+	ClearNodeMaskBits(NodeMask::NODE_MASK_TRAILS);
+	ClearNodeMaskBits(NodeMask::NODE_MASK_ENTITY_BB);
+	SetNodeMaskBits(NodeMask::NODE_MASK_ENTITY_MODEL);
+
+	roadSensors_ = new osg::Group;
+	roadSensors_->setNodeMask(NodeMask::NODE_MASK_ODR_FEATURES);
+	rootnode_->addChild(roadSensors_);
+	trails_ = new osg::Group;
+	trails_->setNodeMask(NodeMask::NODE_MASK_TRAILS);
+	rootnode_->addChild(trails_);
+	odrLines_ = new osg::Group;
+	odrLines_->setNodeMask(NodeMask::NODE_MASK_ODR_FEATURES);
+	rootnode_->addChild(odrLines_);
+	osiLines_ = new osg::Group;
+	osiLines_->setNodeMask(NodeMask::NODE_MASK_OSI_LINES);
+	rootnode_->addChild(osiLines_);
+	osiPoints_ = new osg::Group;
+	osiPoints_->setNodeMask(NodeMask::NODE_MASK_OSI_POINTS);
+	rootnode_->addChild(osiPoints_);
+	exe_path_ = exe_path;
+
+	// add environment
+	if (modelFilename != 0 && strcmp(modelFilename, ""))
+	{
+		std::vector<std::string> file_name_candidates;
+
+		// absolute path or relative to current directory
+		file_name_candidates.push_back(modelFilename);
+
+		// Remove all directories from path and look in current directory
+		file_name_candidates.push_back(FileNameOf(modelFilename));
+
+		// Finally check registered paths 
+		for (size_t i = 0; i < SE_Env::Inst().GetPaths().size(); i++)
+		{
+			file_name_candidates.push_back(CombineDirectoryPathAndFilepath(SE_Env::Inst().GetPaths()[i], modelFilename));
+		}
+		
+		size_t i;
+		for (i = 0; i < file_name_candidates.size(); i++)
+		{
+			if (FileExists(file_name_candidates[i].c_str()))
+			{
+				if (AddEnvironment(file_name_candidates[i].c_str()) == 0)
+				{
+					break;
+				}
+			}
+		}
+
+		if (i == file_name_candidates.size())
+		{
+			LOG("Failed to read environment model %s!", modelFilename);
+		}
+	}
+
+	if (environment_ == 0)
+	{
+		if (odrManager->GetNumOfRoads() > 0)
+		{
+			// No visual model of the road network loaded 
+			// Generate a simplistic 3D model based on OpenDRIVE content
+			LOG("No scenegraph 3D model loaded. Generating a simplistic one...");
+
+			roadGeom = new RoadGeom(odrManager);
+			environment_ = roadGeom->root_;
+			envTx_->addChild(environment_);
+
+			// Since the generated 3D model is based on OSI features, let's hide those
+			ClearNodeMaskBits(NodeMask::NODE_MASK_ODR_FEATURES);
+			ClearNodeMaskBits(NodeMask::NODE_MASK_OSI_LINES);
+		}
+	}
+
+	if (odrManager->GetNumOfRoads() > 0 && !CreateRoadLines(odrManager))
+	{
+		LOG("Viewer::Viewer Failed to create road lines!\n");
+	}
+
+	if (odrManager->GetNumOfRoads() > 0 && !CreateRoadMarkLines(odrManager))
+	{
+		LOG("Viewer::Viewer Failed to create road mark lines!\n");
+	}
+
+	if (odrManager->GetNumOfRoads() > 0 && CreateRoadSignsAndObjects(odrManager) != 0)
+	{
+		LOG("Viewer::Viewer Failed to create road signs!\n");
+	}
+
+#if 0
+	osgViewer_->setSceneData(shadowedScene);
+#else
+	osgViewer_->setSceneData(rootnode_);
+#endif
+
+	// Setup the camera models
+	nodeTrackerManipulator_ = new osgGA::NodeTrackerManipulator;
+	nodeTrackerManipulator_->setTrackerMode(osgGA::NodeTrackerManipulator::NODE_CENTER);
+	nodeTrackerManipulator_->setRotationMode(osgGA::NodeTrackerManipulator::ELEVATION_AZIM);
+	nodeTrackerManipulator_->setVerticalAxisFixed(true);
+
+	osg::ref_ptr<osgGA::TrackballManipulator> trackBallManipulator; 
+	trackBallManipulator = new osgGA::TrackballManipulator;
+	trackBallManipulator->setVerticalAxisFixed(true);
+
+	osg::ref_ptr<osgGA::OrbitManipulator> orbitManipulator;
+	orbitManipulator = new osgGA::OrbitManipulator;
+	orbitManipulator->setVerticalAxisFixed(true);
+
+	rubberbandManipulator_ = new osgGA::RubberbandManipulator(camMode_);
+	rubberbandManipulator_->setTrackNode(envTx_);
+	rubberbandManipulator_->calculateCameraDistance();
+
+	{
+		osg::ref_ptr<osgGA::KeySwitchMatrixManipulator> keyswitchManipulator = new osgGA::KeySwitchMatrixManipulator;
+
+		keyswitchManipulator->addMatrixManipulator('1', "Rubberband", rubberbandManipulator_.get());
+		keyswitchManipulator->addMatrixManipulator('2', "Flight", new osgGA::FlightManipulator());
+		keyswitchManipulator->addMatrixManipulator('3', "Drive", new osgGA::DriveManipulator());
+		keyswitchManipulator->addMatrixManipulator('4', "Terrain", new osgGA::TerrainManipulator());
+		keyswitchManipulator->addMatrixManipulator('5', "Orbit", new osgGA::OrbitManipulator());
+		keyswitchManipulator->addMatrixManipulator('6', "FirstPerson", new osgGA::FirstPersonManipulator());
+		keyswitchManipulator->addMatrixManipulator('7', "Spherical", new osgGA::SphericalManipulator());
+		keyswitchManipulator->addMatrixManipulator('8', "NodeTracker", nodeTrackerManipulator_.get());
+		keyswitchManipulator->addMatrixManipulator('9', "Trackball", trackBallManipulator.get());
+
+		osgViewer_->setCameraManipulator(keyswitchManipulator.get());
+	}
+
+	osgViewer_->addEventHandler(new ViewerEventHandler(this));
+
+	osgViewer_->getCamera()->setLODScale(lodScale_);
+	osgViewer_->getCamera()->setComputeNearFarMode(osg::CullSettings::DO_NOT_COMPUTE_NEAR_FAR);
+	if (!clear_color)
+	{
+		// Default background color
+		osgViewer_->getCamera()->setClearColor(osg::Vec4(0.5f, 0.75f, 1.0f, 0.0f));
+	}
+
+	// add the window size toggle handler
+	osgViewer_->addEventHandler(new osgViewer::WindowSizeHandler);
+
+	// add the stats handler
+	osgViewer_->addEventHandler(new osgViewer::StatsHandler);
+
+	// add the state manipulator
+	osgViewer_->addEventHandler(new osgGA::StateSetManipulator(osgViewer_->getCamera()->getOrCreateStateSet()));
+
+#if 1
+	// add the thread model handler
+	osgViewer_->addEventHandler(new osgViewer::ThreadingHandler);
+#else
+	// If we see problem with chrashes when manipulating graphic nodes or states, in spite of 
+	// trying to use callback mechanisms, then locking to single thread might be a solution. 
+
+	// Hard code single thread model. Can't get setDataVariance(DYNAMIC)
+	// to work with some state changes. And callbacks for all possible
+	// nodes would be too much overhead. Solve when needed.
+	osgViewer_->setThreadingModel(osgViewer::ViewerBase::SingleThreaded);
+#endif
+
+	// add the help handler
+	osgViewer_->addEventHandler(new osgViewer::HelpHandler(arguments.getApplicationUsage()));
+
+	// add the record camera path handler
+	osgViewer_->addEventHandler(new osgViewer::RecordCameraPathHandler);
+
+	// add the LOD Scale handler
+	osgViewer_->addEventHandler(new osgViewer::LODScaleHandler);
+
+	// add the screen capture handler
+	osgViewer_->addEventHandler(new osgViewer::ScreenCaptureHandler);
+
+	osgViewer_->setReleaseContextAtEndOfFrameHint(false);
+
+	// Light
+	osgViewer_->setLightingMode(osg::View::SKY_LIGHT);
+	osg::Light *light = osgViewer_->getLight();
+	light->setPosition(osg::Vec4(50000, -50000, 70000, 1));
+	light->setDirection(osg::Vec3(-1, 1, -1));
+	float ambient = 0.4;
+	light->setAmbient(osg::Vec4(ambient, ambient, 0.9*ambient, 1));
+	light->setDiffuse(osg::Vec4(0.8, 0.8, 0.7, 1));
+
+	osgViewer_->realize();
+
+	// Overlay text
+	osg::ref_ptr<osg::Geode> textGeode = new osg::Geode;
+	osg::Vec4 layoutColor(0.9f, 0.9f, 0.9f, 1.0f);
+	float layoutCharacterSize = 12.0f;
+
+	infoText = new osgText::Text;
+	infoText->setColor(layoutColor);
+	infoText->setCharacterSize(layoutCharacterSize);
+	infoText->setAxisAlignment(osgText::Text::SCREEN);
+	infoText->setPosition(osg::Vec3(10, 10, 0));
+	infoText->setDataVariance(osg::Object::DYNAMIC);
+
+	textGeode->addDrawable(infoText);
+
+	infoTextCamera = new osg::Camera;
+	infoTextCamera->setReferenceFrame(osg::Transform::ABSOLUTE_RF);
+	infoTextCamera->setClearMask(GL_DEPTH_BUFFER_BIT);
+	infoTextCamera->setRenderOrder(osg::Camera::POST_RENDER, 10);
+	infoTextCamera->setAllowEventFocus(false);
+	infoTextCamera->addChild(textGeode.get());
+	infoTextCamera->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF);
+	osg::GraphicsContext* context = dynamic_cast<osgViewer::GraphicsWindow*>(osgViewer_->getCamera()->getGraphicsContext());
+	SetInfoTextProjection(context->getTraits()->width, context->getTraits()->height);
+
+	rootnode_->addChild(infoTextCamera);
+    
+    
+
+}
+
+Viewer::~Viewer()
+{
+	osgViewer_->setDone(true);
+	for (size_t i=0; i< entities_.size(); i++)
+	{
+		delete(entities_[i]);
+	}
+	entities_.clear();
+	delete osgViewer_;
+	osgViewer_ = 0;
+}
+
+void Viewer::SetCameraMode(int mode)
+{
+	if (mode < 0 || mode >= osgGA::RubberbandManipulator::RB_NUM_MODES)
+	{
+		return;
+	}
+
+	camMode_ = mode;
+	rubberbandManipulator_->setMode(camMode_);
+}
+
+EntityModel* Viewer::AddEntityModel(std::string modelFilepath, osg::Vec3 trail_color, EntityModel::EntityType type, 
+	bool road_sensor, std::string name, OSCBoundingBox* boundingBox)
+{
+	// Load 3D model
+	std::string path = modelFilepath;
+	osg::ref_ptr<osg::Group> group = 0;
+
+	std::vector<std::string> file_name_candidates;
+	file_name_candidates.push_back(path);
+	file_name_candidates.push_back(CombineDirectoryPathAndFilepath(DirNameOf(exe_path_) + "/../resources/models", path));
+	// Finally check registered paths 
+	for (size_t i = 0; i < SE_Env::Inst().GetPaths().size(); i++)
+	{
+		file_name_candidates.push_back(CombineDirectoryPathAndFilepath(SE_Env::Inst().GetPaths()[i], path));
+		file_name_candidates.push_back(CombineDirectoryPathAndFilepath(SE_Env::Inst().GetPaths()[i], std::string("../models/" + path)));
+	}
+	for (size_t i = 0; i < file_name_candidates.size(); i++)
+	{
+		if (FileExists(file_name_candidates[i].c_str()))
+		{
+			if (group = LoadEntityModel(file_name_candidates[i].c_str()))
+			{
+				break;
+			}
+		}
+	}
+
+	if (boundingBox || group == 0)
+	{
+		// Create a bounding box visual representation
+
+		if (path == "")
+		{
+			LOG("No filename specified for model! - creating a dummy model");
+		}
+		else if (group == 0)
+		{
+			LOG("Failed to load visual model %s. %s", path.c_str(), file_name_candidates.size() > 1 ? "Also tried the following paths:" : "");
+			for (size_t i = 1; i < file_name_candidates.size(); i++)
+			{
+				LOG("    %s", file_name_candidates[i].c_str());
+			}
+			LOG("Creating a dummy model instead");
+		}
+
+		osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+		geode->addDrawable(new osg::ShapeDrawable(new osg::Box()));
+
+		osg::ref_ptr<osg::Group> bbGroup = new osg::Group;
+		osg::ref_ptr<osg::PositionAttitudeTransform> tx = new osg::PositionAttitudeTransform;
+
+		osg::Material* material = new osg::Material();
+
+		// Set color of vehicle based on its index
+		double* color;
+		double b = 1.5;  // brighness
+		int index = entities_.size() % 4;
+
+		if (index == 0) color = color_white;
+		else if (index == 1) color = color_red;
+		else if (index == 2) color = color_blue;
+		else color = color_yellow;
+
+		material->setDiffuse(osg::Material::FRONT, osg::Vec4(b * color[0], b * color[1], b * color[2], 1.0));
+		material->setAmbient(osg::Material::FRONT, osg::Vec4(b * color[0], b * color[1], b * color[2], 1.0));
+
+		if (group == 0)
+		{
+			// If no model loaded, make a shaded copy of bounding box as model
+			osg::ref_ptr<osg::Geode> geodeCopy = dynamic_cast<osg::Geode*>(geode->clone(osg::CopyOp::DEEP_COPY_ALL));
+			group = new osg::Group;
+			tx->addChild(geodeCopy);
+			geodeCopy->setNodeMask(NodeMask::NODE_MASK_ENTITY_MODEL);
+		}
+
+		// Set dimensions of the entity "box"
+		if (boundingBox)
+		{
+			tx->setScale(osg::Vec3(boundingBox->dimensions_.length_, boundingBox->dimensions_.width_, boundingBox->dimensions_.height_));
+			tx->setPosition(osg::Vec3(boundingBox->center_.x_, boundingBox->center_.y_, boundingBox->center_.z_));
+
+			// Draw only wireframe 
+			osg::PolygonMode* polygonMode = new osg::PolygonMode;
+			polygonMode->setMode(osg::PolygonMode::FRONT_AND_BACK, osg::PolygonMode::LINE);
+			osg::ref_ptr<osg::StateSet> stateset = geode->getOrCreateStateSet(); // Get the StateSet of the group
+			stateset->setAttributeAndModes(polygonMode, osg::StateAttribute::OVERRIDE | osg::StateAttribute::ON);
+			stateset->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+			geode->setNodeMask(NodeMask::NODE_MASK_ENTITY_BB);
+
+			osg::ref_ptr<osg::Geode> center = new osg::Geode;
+			center->addDrawable(new osg::ShapeDrawable(new osg::Sphere(osg::Vec3(0, 0, 0), 0.2)));
+			center->setNodeMask(NodeMask::NODE_MASK_ENTITY_BB);
+			bbGroup->addChild(center);
+		}
+		else
+		{
+			// Scale to something car-ish
+			tx->setScale(osg::Vec3(4.5, 1.8, 1.5));
+			tx->setPosition(osg::Vec3(1.5, 0, 0.75));
+		}
+		tx->addChild(geode);
+		tx->getOrCreateStateSet()->setAttribute(material);
+		bbGroup->setName("BoundingBox");
+		bbGroup->addChild(tx);
+
+		group->addChild(bbGroup);
+		group->setName(name);
+	}
+
+	EntityModel* model;
+	if (type == EntityModel::EntityType::ENTITY_TYPE_VEHICLE)
+	{
+		model = new CarModel(osgViewer_, group, rootnode_, trails_, dot_node_, trail_color, name);
+	}
+	else
+	{
+		model = new EntityModel(osgViewer_, group, rootnode_, trails_, dot_node_, trail_color, name);
+	}
+
+	model->state_set_ = model->lod_->getOrCreateStateSet(); // Creating material
+	model->blend_color_ = new osg::BlendColor(osg::Vec4(1, 1, 1, 1));
+	model->state_set_->setAttributeAndModes(model->blend_color_);
+	model->blend_color_->setDataVariance(osg::Object::DYNAMIC);
+
+	osg::BlendFunc* bf = new osg::BlendFunc(osg::BlendFunc::CONSTANT_ALPHA, osg::BlendFunc::ONE_MINUS_CONSTANT_ALPHA);
+	model->state_set_->setAttributeAndModes(bf);
+	model->state_set_->setMode(GL_DEPTH_TEST, osg::StateAttribute::ON);
+	model->state_set_->setRenderingHint(osg::StateSet::TRANSPARENT_BIN);
+
+	entities_.push_back(model);
+
+	// Focus on first added car
+	if (entities_.size() == 1)
+	{
+		currentCarInFocus_ = 0;
+		rubberbandManipulator_->setTrackNode(entities_.back()->txNode_,
+			rubberbandManipulator_->getMode() == osgGA::RubberbandManipulator::CAMERA_MODE::RB_MODE_TOP ? false : true);
+		nodeTrackerManipulator_->setTrackNode(entities_.back()->txNode_);
+	}
+
+	if (type == EntityModel::EntityType::ENTITY_TYPE_VEHICLE)
+	{
+		CarModel* vehicle = (CarModel*)entities_.back();
+		CreateRoadSensors(vehicle);
+		
+		if (road_sensor)
+		{
+			vehicle->road_sensor_->Show();
+		}
+		else
+		{
+			vehicle->road_sensor_->Hide();
+		}
+	}
+
+	return entities_.back();
+}
+
+void Viewer::RemoveCar(std::string name)
+{
+	for (size_t i = 0; i < entities_.size(); i++) 
+	{
+		if (entities_[i]->name_ == name)
+		{
+			entities_.erase(entities_.begin() + i);
+		}
+	}
+}
+
+osg::ref_ptr<osg::Group> Viewer::LoadEntityModel(const char *filename)
+{
+	osg::ref_ptr<osg::PositionAttitudeTransform> shadow_tx = 0;
+	osg::ref_ptr<osg::Node> node;
+	osg::ref_ptr<osg::Group> group = new osg::Group;
+
+	node = osgDB::readNodeFile(filename);
+	if (!node)
+	{
+		return 0;
+	}
+
+	osg::ComputeBoundsVisitor cbv;
+	node->accept(cbv);
+	osg::BoundingBox boundingBox = cbv.getBoundingBox();
+
+	double xc, yc, dx, dy;
+	dx = boundingBox._max.x() - boundingBox._min.x();
+	dy = boundingBox._max.y() - boundingBox._min.y();
+	xc = (boundingBox._max.x() + boundingBox._min.x()) / 2;
+	yc = (boundingBox._max.y() + boundingBox._min.y()) / 2;
+
+	if (!shadow_node_)
+	{
+		LoadShadowfile(filename);
+	}
+	
+	node->setNodeMask(NodeMask::NODE_MASK_ENTITY_MODEL);
+	group->addChild(node);
+
+	if (shadow_node_)
+	{
+		shadow_tx = new osg::PositionAttitudeTransform;
+		shadow_tx->setPosition(osg::Vec3d(xc, yc, 0.0));
+		shadow_tx->setScale(osg::Vec3d(SHADOW_SCALE*(dx / 2), SHADOW_SCALE*(dy / 2), 1.0));
+		shadow_tx->addChild(shadow_node_);
+
+		shadow_tx->setNodeMask(NodeMask::NODE_MASK_ENTITY_MODEL);
+		group->addChild(shadow_tx);
+	}
+
+
+	return group;
+}
+
+bool Viewer::CreateRoadMarkLines(roadmanager::OpenDrive* od)
+{
+	double z_offset = 0.10;
+	osg::Vec3 point(0, 0, 0);
+
+	for (int r = 0; r < od->GetNumOfRoads(); r++)
+	{
+		roadmanager::Road *road = od->GetRoadByIdx(r);
+		for (int i = 0; i < road->GetNumberOfLaneSections(); i++)
+		{
+			roadmanager::LaneSection *lane_section = road->GetLaneSectionByIdx(i);
+			for (int j = 0; j < lane_section->GetNumberOfLanes(); j++)
+			{
+				roadmanager::Lane *lane = lane_section->GetLaneByIdx(j);
+				for (int k = 0; k < lane->GetNumberOfRoadMarks(); k++)
+				{
+					roadmanager::LaneRoadMark *lane_roadmark = lane->GetLaneRoadMarkByIdx(k);
+					for (int m = 0; m < lane_roadmark->GetNumberOfRoadMarkTypes(); m++)
+					{
+						roadmanager::LaneRoadMarkType * lane_roadmarktype = lane_roadmark->GetLaneRoadMarkTypeByIdx(m);
+						for (int n = 0; n < lane_roadmarktype->GetNumberOfRoadMarkTypeLines(); n++)
+						{
+							roadmanager::LaneRoadMarkTypeLine * lane_roadmarktypeline = lane_roadmarktype->GetLaneRoadMarkTypeLineByIdx(n);
+							roadmanager::OSIPoints curr_osi_rm;
+							curr_osi_rm = lane_roadmarktypeline->GetOSIPoints();
+
+							if (lane_roadmark->GetType() == roadmanager::LaneRoadMark::RoadMarkType::BROKEN)
+							{
+								for (int q = 0; q < curr_osi_rm.GetPoints().size(); q+=2)
+								{
+									roadmanager::OSIPoints::OSIPointStruct osi_point1 = curr_osi_rm.GetPoint(q);
+									roadmanager::OSIPoints::OSIPointStruct osi_point2 = curr_osi_rm.GetPoint(q+1);
+
+									// osg references for road mark osi points
+									osg::ref_ptr<osg::Geometry> osi_rm_geom = new osg::Geometry;
+									osg::ref_ptr<osg::Vec3Array> osi_rm_points = new osg::Vec3Array;
+									osg::ref_ptr<osg::Vec4Array> osi_rm_color = new osg::Vec4Array;
+									osg::ref_ptr<osg::Point> osi_rm_point = new osg::Point();
+									
+									// osg references for drawing lines between each road mark osi points
+									osg::ref_ptr<osg::Geometry> geom = new osg::Geometry;
+									osg::ref_ptr<osg::Vec3Array> points = new osg::Vec3Array;
+									osg::ref_ptr<osg::Vec4Array> color = new osg::Vec4Array;
+									osg::ref_ptr<osg::LineWidth> lineWidth = new osg::LineWidth();
+
+									// start point of each road mark
+									point.set(osi_point1.x, osi_point1.y, osi_point1.z + z_offset);
+									osi_rm_points->push_back(point);
+
+									// end point of each road mark
+									point.set(osi_point2.x, osi_point2.y, osi_point2.z + z_offset);
+									osi_rm_points->push_back(point);
+
+									osi_rm_color->push_back(osg::Vec4(color_white[0], color_white[1], color_white[2], 1.0));
+
+									// Put points at the start and end of the roadmark
+									osi_rm_point->setSize(6.0f);
+									osi_rm_geom->setVertexArray(osi_rm_points.get());
+									osi_rm_geom->setColorArray(osi_rm_color.get());
+									osi_rm_geom->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
+									osi_rm_geom->addPrimitiveSet(new osg::DrawArrays(GL_POINTS, 0, osi_rm_points->size()));
+									osi_rm_geom->getOrCreateStateSet()->setAttributeAndModes(osi_rm_point, osg::StateAttribute::ON);
+									osi_rm_geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+									osiPoints_->addChild(osi_rm_geom);
+
+									// Draw lines from the start of the roadmark to the end of the roadmark
+									lineWidth->setWidth(OSI_LINE_WIDTH);
+									geom->setVertexArray(osi_rm_points.get());
+									geom->setColorArray(osi_rm_color.get());
+									geom->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
+									geom->addPrimitiveSet(new osg::DrawArrays(GL_LINE_STRIP, 0, osi_rm_points->size()));
+									geom->getOrCreateStateSet()->setAttributeAndModes(lineWidth, osg::StateAttribute::ON);
+									geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+									osiLines_->addChild(geom);
+								}
+							}
+							else if(lane_roadmark->GetType() == roadmanager::LaneRoadMark::RoadMarkType::SOLID)
+							{
+								// osg references for road mark osi points
+								osg::ref_ptr<osg::Geometry> osi_rm_geom = new osg::Geometry;
+								osg::ref_ptr<osg::Vec3Array> osi_rm_points = new osg::Vec3Array;
+								osg::ref_ptr<osg::Vec4Array> osi_rm_color = new osg::Vec4Array;
+								osg::ref_ptr<osg::Point> osi_rm_point = new osg::Point();
+									
+								// osg references for drawing lines between each road mark osi points
+								osg::ref_ptr<osg::Geometry> geom = new osg::Geometry;
+								osg::ref_ptr<osg::Vec3Array> points = new osg::Vec3Array;
+								osg::ref_ptr<osg::Vec4Array> color = new osg::Vec4Array;
+								osg::ref_ptr<osg::LineWidth> lineWidth = new osg::LineWidth();
+
+								// Creating points for the given roadmark
+								for (int s = 0; s < curr_osi_rm.GetPoints().size(); s++)
+								{
+									point.set(curr_osi_rm.GetPoint(s).x, curr_osi_rm.GetPoint(s).y, curr_osi_rm.GetPoint(s).z + z_offset);
+									osi_rm_points->push_back(point);
+									osi_rm_color->push_back(osg::Vec4(color_white[0], color_white[1], color_white[2], 1.0));
+								}
+
+								// Put points on selected locations
+								osi_rm_point->setSize(6.0f);
+								osi_rm_geom->setVertexArray(osi_rm_points.get());
+								osi_rm_geom->setColorArray(osi_rm_color.get());
+								osi_rm_geom->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
+								osi_rm_geom->addPrimitiveSet(new osg::DrawArrays(GL_POINTS, 0, osi_rm_points->size()));
+								osi_rm_geom->getOrCreateStateSet()->setAttributeAndModes(osi_rm_point, osg::StateAttribute::ON);
+								osi_rm_geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+									
+								osiPoints_->addChild(osi_rm_geom);
+
+								// Draw lines between each selected points
+								lineWidth->setWidth(OSI_LINE_WIDTH);
+								color->push_back(osg::Vec4(color_white[0], color_white[1], color_white[2], 1.0));
+
+								geom->setVertexArray(osi_rm_points.get());
+								geom->setColorArray(color.get());
+								geom->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
+								geom->addPrimitiveSet(new osg::DrawArrays(GL_LINE_STRIP, 0, osi_rm_points->size()));
+								geom->getOrCreateStateSet()->setAttributeAndModes(lineWidth, osg::StateAttribute::ON);
+								geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+								osiLines_->addChild(geom);
+
+							}
+						}
+					}
+				}
+			}
+		}
+	}
+
+	return true;
+}
+
+bool Viewer::CreateRoadLines(roadmanager::OpenDrive* od)
+{
+	double z_offset = 0.10;
+	roadmanager::Position* pos = new roadmanager::Position();
+	osg::Vec3 point(0, 0, 0);
+
+	roadmanager::OSIPoints* curr_osi;
+
+	for (int r = 0; r < od->GetNumOfRoads(); r++)
+	{
+		roadmanager::Road *road = od->GetRoadByIdx(r);
+
+		// Road key points
+		osg::ref_ptr<osg::Geometry> kp_geom = new osg::Geometry;
+		osg::ref_ptr<osg::Vec3Array> kp_points = new osg::Vec3Array;
+		osg::ref_ptr<osg::Vec4Array> kp_color = new osg::Vec4Array;
+		osg::ref_ptr<osg::Point> kp_point = new osg::Point();
+
+		roadmanager::Geometry *geom = nullptr;
+		for (int i = 0; i < road->GetNumberOfGeometries()+1; i++)
+		{
+			if (i < road->GetNumberOfGeometries())
+			{
+				geom = road->GetGeometry(i);
+				pos->SetTrackPos(road->GetId(), geom->GetS(), 0);
+			}
+			else
+			{
+				pos->SetTrackPos(road->GetId(), geom->GetS()+geom->GetLength(), 0);
+			}
+
+			point.set(pos->GetX(), pos->GetY(), pos->GetZ() + z_offset);
+			kp_points->push_back(point);
+
+			if (i == 0)
+			{
+				kp_color->push_back(osg::Vec4(color_yellow[0], color_yellow[1], color_yellow[2], 1.0));
+			}
+			else
+			{
+				kp_color->push_back(osg::Vec4(color_red[0], color_red[1], color_red[2], 1.0));
+			}
+		}
+
+		kp_point->setSize(12.0f);
+		kp_geom->setVertexArray(kp_points.get());
+		kp_geom->setColorArray(kp_color.get());
+		kp_geom->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
+		kp_geom->addPrimitiveSet(new osg::DrawArrays(GL_POINTS, 0, kp_points->size()));
+		kp_geom->getOrCreateStateSet()->setAttributeAndModes(kp_point, osg::StateAttribute::ON);
+		kp_geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+		odrLines_->addChild(kp_geom);
+
+		for (int i = 0; i < road->GetNumberOfLaneSections(); i++)
+		{
+			roadmanager::LaneSection *lane_section = road->GetLaneSectionByIdx(i);
+			for (int j = 0; j < lane_section->GetNumberOfLanes(); j++)
+			{
+				roadmanager::Lane *lane = lane_section->GetLaneByIdx(j);
+
+				// visualize both lane center and lane boundary 
+				for (int k = 0; k < 2; k++)
+				{
+					// skip lane center for all non driving lanes except center lane
+					if ((k == 0 && lane->GetId() != 0 && !lane->IsDriving()) ||
+						// skip lane boundary for center lane
+						(k == 1 && lane->GetId() == 0))
+					{
+						continue;
+					}
+					// osg references for osi points on the lane center
+					osg::ref_ptr<osg::Geometry> osi_geom = new osg::Geometry;
+					osg::ref_ptr<osg::Vec3Array> osi_points = new osg::Vec3Array;
+					osg::ref_ptr<osg::Vec4Array> osi_color = new osg::Vec4Array;
+					osg::ref_ptr<osg::Point> osi_point = new osg::Point();
+
+					// osg references for drawing lines on the lane center using osi points
+					osg::ref_ptr<osg::Geometry> line_geom = new osg::Geometry;
+					osg::ref_ptr<osg::Vec3Array> points = new osg::Vec3Array;
+					osg::ref_ptr<osg::Vec4Array> color = new osg::Vec4Array;
+					osg::ref_ptr<osg::LineWidth> lineWidth = new osg::LineWidth();
+
+					if (k == 0)
+					{
+						curr_osi = lane->GetOSIPoints();
+					}
+					else
+					{
+						curr_osi = lane->GetLaneBoundary()->GetOSIPoints();
+					}
+
+					if (curr_osi == 0)
+					{
+						continue;
+					}
+
+					for (int m = 0; m < curr_osi->GetPoints().size(); m++)
+					{
+						roadmanager::OSIPoints::OSIPointStruct osi_point_s = curr_osi->GetPoint(m);
+						point.set(osi_point_s.x, osi_point_s.y, osi_point_s.z + z_offset);
+						osi_points->push_back(point);
+						osi_color->push_back(osg::Vec4(color_blue[0], color_blue[1], color_blue[2], 1.0));
+					}
+					osi_point->setSize(6.0f);
+					osi_geom->setVertexArray(osi_points.get());
+					osi_geom->setColorArray(osi_color.get());
+					osi_geom->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
+					osi_geom->addPrimitiveSet(new osg::DrawArrays(GL_POINTS, 0, osi_points->size()));
+					osi_geom->getOrCreateStateSet()->setAttributeAndModes(osi_point, osg::StateAttribute::ON);
+					osi_geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+					
+					osiPoints_->addChild(osi_geom);
+
+					if (lane->GetId() == 0)
+					{
+						lineWidth->setWidth(4.0f);
+						color->push_back(osg::Vec4(color_red[0], color_red[1], color_red[2], 1.0));
+					}
+					else if (k==0)
+					{
+						lineWidth->setWidth(1.5f);
+						color->push_back(osg::Vec4(color_blue[0], color_blue[1], color_blue[2], 1.0));
+					}
+					else 
+					{
+						lineWidth->setWidth(1.5f);
+						color->push_back(osg::Vec4(color_gray[0], color_gray[1], color_gray[2], 1.0));
+					}
+
+					line_geom->setVertexArray(osi_points.get());
+					line_geom->setColorArray(color.get());
+					line_geom->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
+					line_geom->addPrimitiveSet(new osg::DrawArrays(GL_LINE_STRIP, 0, osi_points->size()));
+					line_geom->getOrCreateStateSet()->setAttributeAndModes(lineWidth, osg::StateAttribute::ON);
+					line_geom->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+					odrLines_->addChild(line_geom);
+				}
+			}
+		}
+	}
+
+	delete pos;
+
+	return true;
+}
+
+int Viewer::CreateOutlineObject(roadmanager::Outline *outline)
+{
+	if (outline == 0) return -1;
+	bool roof = outline->closed_ ? true : false;
+	
+	// nrPoints will be corners + 1 if the outline should be closed, reusing first corner as last
+	int nrPoints = outline->closed_ ? outline->corner_.size() + 1 : outline->corner_.size();
+
+	osg::ref_ptr<osg::Group> group = new osg::Group();
+	osg::Vec4 color = osg::Vec4(0.5f, 0.5f, 0.5f, 1.0f);
+	osg::ref_ptr<osg::Vec4Array> color_outline = new osg::Vec4Array;
+	color_outline->push_back(color);
+
+	osg::ref_ptr<osg::Vec3Array> vertices_sides = new osg::Vec3Array(nrPoints * 2);  // one set at bottom and one at top
+	osg::ref_ptr<osg::Vec3Array> vertices_top = new osg::Vec3Array(nrPoints);  // one set at bottom and one at top
+
+	// Set vertices
+	for (size_t i = 0; i < outline->corner_.size(); i++)
+	{
+		double x, y, z;
+		roadmanager::OutlineCorner* corner = outline->corner_[i];
+		corner->GetPos(x, y, z);
+		(*vertices_sides)[i * 2 + 0].set(x, y, z + corner->GetHeight());
+		(*vertices_sides)[i * 2 + 1].set(x, y, z);
+		(*vertices_top)[i].set(x, y, z + corner->GetHeight());
+	}
+
+	// Close geometry
+	if (outline->closed_)
+	{
+		(*vertices_sides)[2 * nrPoints - 2].set((*vertices_sides)[0]);
+		(*vertices_sides)[2 * nrPoints - 1].set((*vertices_sides)[1]);
+		(*vertices_top)[nrPoints-1].set((*vertices_top)[0]);
+	}
+
+	// Finally create and add geometry
+	osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+	osg::ref_ptr<osg::Geometry> geom[] = { new osg::Geometry, new osg::Geometry };
+
+	geom[0]->setVertexArray(vertices_sides.get());
+	geom[0]->addPrimitiveSet(new osg::DrawArrays(GL_QUAD_STRIP, 0, 2 * nrPoints));
+
+	if (roof)
+	{
+		geom[1]->setVertexArray(vertices_top.get());
+		geom[1]->addPrimitiveSet(new osg::DrawArrays(GL_POLYGON, 0, nrPoints));
+		osgUtil::Tessellator tessellator;
+		tessellator.retessellatePolygons(*geom[1]);
+	}
+
+	int nrGeoms = roof ? 2 : 1;
+	for (int i = 0; i < nrGeoms; i++)
+	{
+		osgUtil::SmoothingVisitor::smooth(*geom[i], 0.5);
+		geom[i]->setColorArray(color_outline);
+		geom[i]->setColorBinding(osg::Geometry::BIND_OVERALL);
+		geom[i]->setDataVariance(osg::Object::STATIC);
+		geom[i]->setUseDisplayList(true);
+		geode->addDrawable(geom[i]);
+	}
+
+	osg::ref_ptr<osg::Material> material_ = new osg::Material;
+	material_->setDiffuse(osg::Material::FRONT_AND_BACK, color);
+	material_->setAmbient(osg::Material::FRONT_AND_BACK, color);
+	geode->getOrCreateStateSet()->setAttributeAndModes(material_.get());
+
+	group->addChild(geode);
+	envTx_->addChild(group);
+
+	return 0;
+}
+
+int Viewer::LoadRoadFeature(roadmanager::Road *road, std::string filename, double s, double t, 
+	double z_offset, double scale_x, double scale_y, double scale_z, double heading_offset)
+{
+	roadmanager::Position* pos = new roadmanager::Position();
+	osg::ref_ptr<osg::Node> node;
+	osg::ref_ptr<osg::PositionAttitudeTransform> xform;
+
+	// Load file, try multiple paths
+	std::vector<std::string> file_name_candidates;
+	file_name_candidates.push_back(filename);
+	file_name_candidates.push_back(CombineDirectoryPathAndFilepath(DirNameOf(exe_path_) + "/../resources/models", filename));
+	// Finally check registered paths 
+	for (size_t i = 0; i < SE_Env::Inst().GetPaths().size(); i++)
+	{
+		file_name_candidates.push_back(CombineDirectoryPathAndFilepath(SE_Env::Inst().GetPaths()[i], filename));
+		file_name_candidates.push_back(CombineDirectoryPathAndFilepath(SE_Env::Inst().GetPaths()[i], std::string("../models/" + filename)));
+	}
+	for (size_t i = 0; i < file_name_candidates.size(); i++)
+	{
+		if (FileExists(file_name_candidates[i].c_str()))
+		{
+			node = osgDB::readNodeFile(file_name_candidates[i]);
+			if (!node)
+			{
+				return 0;
+			}
+			pos->SetTrackPos(road->GetId(), s, t);
+			xform = new osg::PositionAttitudeTransform;
+			xform->setPosition(osg::Vec3(pos->GetX(), pos->GetY(), z_offset + pos->GetZ()));
+			xform->setAttitude(osg::Quat(pos->GetH() + heading_offset, osg::Vec3(0, 0, 1)));
+			xform->setScale(osg::Vec3(scale_x, scale_y, scale_z));
+			xform->addChild(node);
+			rootnode_->addChild(xform);
+		}
+	}
+
+	return 0;
+}
+
+int Viewer::CreateRoadSignsAndObjects(roadmanager::OpenDrive* od)
+{
+	for (int r = 0; r < od->GetNumOfRoads(); r++)
+	{
+		roadmanager::Road* road = od->GetRoadByIdx(r);
+		for (size_t s = 0; s < road->GetNumberOfSignals(); s++)
+		{
+			roadmanager::Signal* signal = road->GetSignal(s);
+			double orientation = signal->GetOrientation() == roadmanager::Signal::Orientation::NEGATIVE ? M_PI : 0.0;
+			if (LoadRoadFeature(road, signal->GetName() + ".osgb", signal->GetS(), signal->GetT(), signal->GetZOffset(), 1.0, 1.0, 1.0, orientation + signal->GetHOffset()) != 0)
+			{
+				return -1;
+			}
+		}
+
+		for (size_t o = 0; o < road->GetNumberOfObjects(); o++)
+		{
+			roadmanager::Object* object = road->GetObject(o);
+			if (object->GetNumberOfOutlines() > 0)
+			{
+				for (size_t j = 0; j < object->GetNumberOfOutlines(); j++)
+				{
+					roadmanager::Outline* outline = object->GetOutline(j);
+					CreateOutlineObject(outline);
+				}
+				LOG("Created outline geometry for object %s.", object->GetName().c_str());
+				LOG("  if it looks strange, e.g.faces too dark or light color, ");
+				LOG("  check that corners are defined counter-clockwise (as OpenGL default).");
+			}
+			else
+			{
+				// Assume name is representing a 3D model filename
+				double orientation = object->GetOrientation() == roadmanager::Signal::Orientation::NEGATIVE ? M_PI : 0.0;
+				if (LoadRoadFeature(road, object->GetName() + ".osgb", object->GetS(), object->GetT(), object->GetZOffset(),
+					1.0, 1.0, object->GetHeight(), orientation + object->GetHOffset()) != 0)
+				{
+					return -1;
+				}
+			}
+		}
+	}
+
+	return 0;
+}
+
+bool Viewer::CreateRoadSensors(CarModel *vehicle_model)
+{
+	vehicle_model->road_sensor_ = CreateSensor(color_yellow, true, false, 0.25, 2.5);
+	vehicle_model->lane_sensor_ = CreateSensor(color_yellow, true, true, 0.25, 2.5);
+
+	return true;
+}
+
+PointSensor* Viewer::CreateSensor(double color[], bool create_ball, bool create_line, double ball_radius, double line_width)
+{
+	PointSensor *sensor = new PointSensor();
+	sensor->group_ = new osg::Group();
+
+	// Point
+	if (create_ball)
+	{
+		osg::ref_ptr<osg::Geode> geode = new osg::Geode;
+		geode->addDrawable(new osg::ShapeDrawable(new osg::Sphere()));
+		sensor->ball_ = new osg::PositionAttitudeTransform;
+		sensor->ball_->setScale(osg::Vec3(ball_radius, ball_radius, ball_radius));
+		sensor->ball_->addChild(geode);
+		
+		osg::ref_ptr<osg::Material> material = new osg::Material();
+		material->setDiffuse(osg::Material::FRONT, osg::Vec4(color[0], color[1], color[2], 1.0));
+		material->setAmbient(osg::Material::FRONT, osg::Vec4(color[0], color[1], color[2], 1.0));
+		sensor->ball_->getOrCreateStateSet()->setAttribute(material);
+		sensor->ball_radius_ = ball_radius;
+		sensor->group_->addChild(sensor->ball_);
+	}
+
+	// line
+	if (create_line)
+	{
+		sensor->line_vertex_data_ = new osg::Vec3Array;
+		sensor->line_vertex_data_->push_back(osg::Vec3d(0, 0, 0));
+		sensor->line_vertex_data_->push_back(osg::Vec3d(0, 0, 0));
+
+		osg::ref_ptr<osg::Group> group = new osg::Group;
+		sensor->line_ = new osg::Geometry();
+		group->addChild(sensor->line_);
+		//sensor->line_->setCullingActive(false);
+		sensor->line_->setVertexArray(sensor->line_vertex_data_.get());
+		sensor->line_->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP, 0, 2));
+
+		osg::ref_ptr<osg::LineWidth> lineWidth = new osg::LineWidth();
+		lineWidth->setWidth(line_width);
+		sensor->line_->getOrCreateStateSet()->setAttributeAndModes(lineWidth, osg::StateAttribute::ON);
+		sensor->line_->getOrCreateStateSet()->setMode(GL_LIGHTING, osg::StateAttribute::OFF | osg::StateAttribute::OVERRIDE);
+
+		osg::ref_ptr<osg::Vec4Array> color_ = new osg::Vec4Array;
+		color_->push_back(osg::Vec4(color[0], color[1], color[2], 1.0));
+		sensor->line_->setColorArray(color_.get());
+		sensor->line_->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE_SET);
+		//sensor->line_->setDataVariance(osg::Object::DYNAMIC);
+		sensor->group_->addChild(group);
+	}
+
+	// Make sensor visible as default
+	roadSensors_->addChild(sensor->group_);
+	sensor->Show();
+
+	return sensor;
+}
+
+void Viewer::UpdateRoadSensors(PointSensor *road_sensor, PointSensor *lane_sensor, roadmanager::Position *pos) 
+{
+	if (road_sensor == 0 || lane_sensor == 0)
+	{
+		return;
+	}
+
+	roadmanager::Position track_pos(*pos);
+	track_pos.SetTrackPos(pos->GetTrackId(), pos->GetS(), 0);
+
+	SensorSetPivotPos(road_sensor, pos->GetX(), pos->GetY(), pos->GetZ());
+	SensorSetTargetPos(road_sensor, track_pos.GetX(), track_pos.GetY(), track_pos.GetZ());
+	UpdateSensor(road_sensor);
+
+	roadmanager::Position lane_pos(*pos);
+	lane_pos.SetLanePos(pos->GetTrackId(), pos->GetLaneId(), pos->GetS(), 0);
+
+	SensorSetPivotPos(lane_sensor, pos->GetX(), pos->GetY(), pos->GetZ());
+	SensorSetTargetPos(lane_sensor, lane_pos.GetX(), lane_pos.GetY(), lane_pos.GetZ());
+	UpdateSensor(lane_sensor);
+}
+
+void Viewer::SensorSetPivotPos(PointSensor *sensor, double x, double y, double z)
+{
+	double z_offset = 0.2;
+	sensor->pivot_pos = osg::Vec3(x, y, z + MAX(sensor->ball_radius_ / 3.0, z_offset));
+}
+
+void Viewer::SensorSetTargetPos(PointSensor *sensor, double x, double y, double z)
+{
+	double z_offset = 0.2;
+	sensor->target_pos = osg::Vec3(x, y, z + MAX(sensor->ball_radius_ / 3.0, z_offset));
+}
+
+void Viewer::UpdateSensor(PointSensor *sensor)
+{
+	if (sensor == 0)
+	{
+		return;
+	}
+
+	// Line
+	if (sensor->line_)
+	{
+		sensor->line_vertex_data_->clear();
+		sensor->line_vertex_data_->push_back(sensor->pivot_pos);
+		sensor->line_vertex_data_->push_back(sensor->target_pos);
+		sensor->line_->dirtyGLObjects();
+		sensor->line_->dirtyBound();
+		sensor->line_vertex_data_->dirty();
+	}
+
+	// Point/ball
+	if (sensor->ball_)
+	{
+		sensor->ball_->setPosition(sensor->target_pos);
+	}
+}
+
+int Viewer::LoadShadowfile(std::string vehicleModelFilename)
+{
+	// Load shadow geometry - assume it resides in the same resource folder as the vehicle model
+	std::string shadowFilename = DirNameOf(vehicleModelFilename).append("/" + std::string(SHADOW_MODEL_FILEPATH));
+	if (FileExists(shadowFilename.c_str()))
+	{
+		shadow_node_ = osgDB::readNodeFile(shadowFilename);
+	}
+
+	if (!shadow_node_)
+	{
+		LOG("Failed to locate shadow model %s based on vehicle model filename %s - continue without", 
+			SHADOW_MODEL_FILEPATH, vehicleModelFilename.c_str());
+		return -1;
+	}
+
+	return 0;
+}
+
+int Viewer::AddEnvironment(const char* filename)
+{
+	// remove current model, if any
+	if (environment_ != 0)
+	{
+		printf("Removing current env\n");
+		envTx_->removeChild(environment_);
+	}
+
+	// load and apply new model
+	// First, assume absolute path or relative current directory
+	if (strcmp(FileNameOf(filename).c_str(), ""))
+	{
+		if ((environment_ = osgDB::readNodeFile(filename)) == 0)
+		{
+			return -1;
+		}
+
+		envTx_->addChild(environment_);
+	} 
+	else
+	{
+		LOG("AddEnvironment: No environment 3D model specified (%s) - go ahead without\n", filename);
+	}
+
+	return 0;
+}
+
+void Viewer::ShowInfoText(bool show)
+{
+	showInfoText = show;
+}
+
+void Viewer::SetInfoText(const char* text)
+{
+	if (showInfoText)
+	{
+		infoText->setText(text);
+	}
+	else
+	{
+		infoText->setText("");
+	}
+}
+
+void Viewer::SetNodeMaskBits(int bits)
+{
+	osgViewer_->getCamera()->setCullMask(osgViewer_->getCamera()->getCullMask() | bits);
+}
+
+void Viewer::SetNodeMaskBits(int mask, int bits)
+{
+	osgViewer_->getCamera()->setCullMask((osgViewer_->getCamera()->getCullMask() & ~mask) | bits);
+}
+
+void Viewer::ClearNodeMaskBits(int bits)
+{
+	osgViewer_->getCamera()->setCullMask(osgViewer_->getCamera()->getCullMask() & ~bits);
+}
+
+void Viewer::ToggleNodeMaskBits(int bits)
+{
+	osgViewer_->getCamera()->setCullMask(osgViewer_->getCamera()->getCullMask() ^ bits);
+}
+
+int Viewer::GetNodeMaskBit(int mask)
+{
+	return osgViewer_->getCamera()->getCullMask() & mask;
+}
+
+void Viewer::SetInfoTextProjection(int width, int height)
+{
+	infoTextCamera->setProjectionMatrix(osg::Matrix::ortho2D(0, width, 0, height));
+}
+
+void Viewer::SetVehicleInFocus(int idx)
+{
+	currentCarInFocus_ = idx;
+	if (entities_.size() > idx)
+	{
+		rubberbandManipulator_->setTrackNode(entities_[currentCarInFocus_]->txNode_, false);
+		nodeTrackerManipulator_->setTrackNode(entities_[currentCarInFocus_]->txNode_);
+	}
+}
+
+void Viewer::SetWindowTitle(std::string title)
+{
+	// Decorate window border with application name
+	osgViewer::ViewerBase::Windows wins;
+	osgViewer_->getWindows(wins);
+	if (wins.size() > 0)
+	{
+		wins[0]->setWindowName(title);
+	}
+}
+
+void Viewer::SetWindowTitleFromArgs(std::vector<std::string> &args)
+{
+	std::string titleString;
+	for (int i = 0; i < args.size(); i++)
+	{
+		std::string arg = args[i];
+		if (i == 0)
+		{
+			arg = FileNameWithoutExtOf(arg);
+			if (arg != "esmini")
+			{
+				arg = "esmini " + arg;
+			}
+		}
+		else if (arg == "--osc" || arg == "--odr" || arg == "--model")
+		{
+			titleString += std::string(arg) + " ";
+			i++;
+			arg = FileNameOf(std::string(args[i]));
+		}
+		else if (arg == "--window")
+		{
+			i += 4;
+			continue;
+		}
+
+		titleString += std::string(arg) + " ";
+	}
+	
+	SetWindowTitle(titleString);
+}
+
+void Viewer::SetWindowTitleFromArgs(int argc, char* argv[])
+{
+	std::vector<std::string> args;
+
+	for (int i = 0; i < argc; i++)
+	{
+		args.push_back(argv[i]);
+	}
+
+	SetWindowTitleFromArgs(args);
+}
+
+void Viewer::RegisterKeyEventCallback(KeyEventCallbackFunc func, void* data)
+{
+	KeyEventCallback cb;
+	cb.func = func;
+	cb.data = data;
+	callback_.push_back(cb);
+}
+
+bool ViewerEventHandler::handle(const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter&)
+{
+	switch (ea.getEventType())
+	{
+	case(osgGA::GUIEventAdapter::RESIZE):
+		viewer_->SetInfoTextProjection(ea.getWindowWidth(), ea.getWindowHeight());
+		break;
+	}
+
+	switch (ea.getKey())
+	{
+	case(osgGA::GUIEventAdapter::KEY_K):
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->camMode_ += 1;
+			if (viewer_->camMode_ >= osgGA::RubberbandManipulator::RB_NUM_MODES)
+			{
+				viewer_->camMode_ = 0;
+			}
+			viewer_->rubberbandManipulator_->setMode(viewer_->camMode_);
+		}
+		break;
+	case(osgGA::GUIEventAdapter::KEY_O):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->ToggleNodeMaskBits(viewer::NodeMask::NODE_MASK_ODR_FEATURES);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_U):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->ToggleNodeMaskBits(viewer::NodeMask::NODE_MASK_OSI_LINES);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Y):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->ToggleNodeMaskBits(viewer::NodeMask::NODE_MASK_OSI_POINTS);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_P):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->ToggleNodeMaskBits(NodeMask::NODE_MASK_ENV_MODEL);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Right):
+	{
+		viewer_->setKeyRight(ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN);
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Left):
+	{
+		viewer_->setKeyLeft(ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN);
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Up):
+	{
+		viewer_->setKeyUp(ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN);
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Down):
+	{
+		viewer_->setKeyDown(ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN);
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Tab):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			int idx = viewer_->currentCarInFocus_ + ((ea.getModKeyMask() & osgGA::GUIEventAdapter::KEY_Shift_L) ? -1 : 1);
+
+			if (idx >= (int)viewer_->entities_.size())
+			{
+				idx = 0;
+			}
+			else if (idx < 0)
+			{
+				idx = viewer_->entities_.size() - 1;
+			}
+
+			viewer_->SetVehicleInFocus(idx);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Comma):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			int mask = viewer_->GetNodeMaskBit(
+				viewer::NodeMask::NODE_MASK_ENTITY_MODEL |
+				viewer::NodeMask::NODE_MASK_ENTITY_BB) / viewer::NodeMask::NODE_MASK_ENTITY_MODEL;
+
+			// Toggle between modes: 0: none, 1: model only, 2: bounding box, 3. model + Bounding box 
+			mask = ((mask + 1) % 4) * viewer::NodeMask::NODE_MASK_ENTITY_MODEL;
+
+			viewer_->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_ENTITY_MODEL |
+				viewer::NodeMask::NODE_MASK_ENTITY_BB, mask);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_I):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->showInfoText = !viewer_->showInfoText;
+			viewer_->infoTextCamera->setNodeMask(viewer_->showInfoText ? 0xffffffff : 0x0);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_J):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->ToggleNodeMaskBits(viewer::NodeMask::NODE_MASK_TRAILS);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_R):
+	{
+		if (ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN)
+		{
+			viewer_->ToggleNodeMaskBits(viewer::NodeMask::NODE_MASK_OBJECT_SENSORS);
+		}
+	}
+	break;
+	case(osgGA::GUIEventAdapter::KEY_Escape):
+	{
+		viewer_->SetQuitRequest(true);
+		viewer_->osgViewer_->setDone(true);
+	}
+	break;
+	}
+
+	// Send key event to registered callback subscribers
+	if (ea.getKey() > 0)
+	{
+		for (size_t i = 0; i < viewer_->callback_.size(); i++)
+		{
+			KeyEvent ke = { ea.getKey(), ea.getModKeyMask(),  ea.getEventType() & osgGA::GUIEventAdapter::KEYDOWN ? true : false };
+			viewer_->callback_[i].func(&ke, viewer_->callback_[i].data);
+		}
+	}
+
+	if (ea.getKey() == osgGA::GUIEventAdapter::KEY_Space)
+	{
+		// prevent OSG "view reset" action on space key
+		return true;
+	}
+	else
+	{
+		// forward all other key events to OSG
+		return false;
+	}
+}

+ 382 - 0
src/ui/ui_osgviewer/viewer.hpp

@@ -0,0 +1,382 @@
+/* 
+ * esmini - Environment Simulator Minimalistic 
+ * https://github.com/esmini/esmini
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this
+ * file, You can obtain one at https://mozilla.org/MPL/2.0/.
+ * 
+ * Copyright (c) partners of Simulation Scenarios
+ * https://sites.google.com/view/simulationscenarios
+ */
+
+#ifndef VIEWER_HPP_
+#define VIEWER_HPP_
+
+#include <osg/PositionAttitudeTransform>
+#include <osgViewer/Viewer>
+#include <osgGA/NodeTrackerManipulator>
+#include <osg/MatrixTransform>
+#include <osg/Material>
+#include <osgText/Text>
+#include <osgAnimation/EaseMotion>
+#include <osg/BlendColor>
+#include <string>
+
+#include "RubberbandManipulator.hpp"
+#include "IdealSensor.hpp"
+#include "RoadManager.hpp"
+#include "CommonMini.hpp"
+#include "roadgeom.hpp"
+
+#define TRAIL_DOT_FADE_DURATION 3.0  // seconds
+#define TRAIL_DOTS_DT 0.5
+#define TRAIL_MAX_DOTS 50
+#define TRAIL_DOT_LIFE_SPAN (0.5 * TRAIL_MAX_DOTS * TRAIL_DOTS_DT) // Start fade when half of the dots have been launched (seconds)
+
+extern double color_green[3];
+extern double color_gray[3];
+extern double color_dark_gray[3];
+extern double color_red[3];
+extern double color_blue[3];
+extern double color_yellow[3];
+extern double color_white[3];
+
+using namespace scenarioengine;
+
+namespace viewer
+{
+	typedef enum
+	{
+		NODE_MASK_NONE =           (0),
+		NODE_MASK_OBJECT_SENSORS = (1 << 0),
+		NODE_MASK_TRAILS =         (1 << 1),
+		NODE_MASK_ODR_FEATURES =   (1 << 2),
+		NODE_MASK_OSI_POINTS =     (1 << 3),
+		NODE_MASK_OSI_LINES =      (1 << 4),
+		NODE_MASK_ENV_MODEL =      (1 << 5),
+		NODE_MASK_ENTITY_MODEL =   (1 << 6),
+		NODE_MASK_ENTITY_BB =      (1 << 7),
+		NODE_MASK_INFO =           (1 << 8),
+		NODE_MASK_ROAD_SENSORS =   (1 << 9),
+	} NodeMask;
+
+	class Line
+	{
+	public:
+		osg::ref_ptr<osg::Geometry> line_;
+		osg::ref_ptr<osg::Vec3Array> line_vertex_data_;
+
+		Line(double x0, double y0, double z0, double x1, double y1, double z1, double r, double g, double b);
+		void SetPoints(double x0, double y0, double z0, double x1, double y1, double z1);
+	};
+
+	class SensorViewFrustum
+	{
+	public:
+		osg::ref_ptr<osg::PositionAttitudeTransform> txNode_;
+		osg::ref_ptr<osg::Group> line_group_;
+		std::vector<Line*> lines_;
+		ObjectSensor *sensor_;
+
+		SensorViewFrustum(ObjectSensor *sensor, osg::Group *parent);
+		~SensorViewFrustum();
+		void Update();
+	};
+
+	class AlphaFadingCallback : public osg::StateAttributeCallback
+	{
+	public:
+		AlphaFadingCallback(osgViewer::Viewer *viewer, osg::Vec4 color)
+		{
+			_motion = new osgAnimation::InCubicMotion(0.0f, TRAIL_DOT_FADE_DURATION);
+			color_ = color;
+			viewer_ = viewer;
+			Reset();
+		}
+		virtual void operator()(osg::StateAttribute*, osg::NodeVisitor*);
+		void Reset() 
+		{ 
+			born_time_stamp_ = viewer_->elapsedTime();
+			time_stamp_ = born_time_stamp_;
+			_motion->reset(); 
+		}
+
+	protected:
+		osg::ref_ptr<osgAnimation::InCubicMotion> _motion;
+
+	private:
+		osg::Vec4 color_;
+		double time_stamp_;
+		double born_time_stamp_;
+		osgViewer::Viewer *viewer_;
+	};
+
+	class TrailDot
+	{
+	public:
+		osg::ref_ptr<osg::PositionAttitudeTransform> dot_;
+		osg::ref_ptr<osg::Material> material_;
+
+		TrailDot(double x, double y, double z, double heading,
+			osgViewer::Viewer *viewer, osg::Group *parent, osg::ref_ptr<osg::Node> dot_node, osg::Vec4 trail_color);
+		void Reset(double x, double y, double z, double heading);
+
+	private:
+		osg::ref_ptr<AlphaFadingCallback> fade_callback_;
+	};
+
+	class Trail
+	{
+	public:
+		TrailDot* dot_[TRAIL_MAX_DOTS];
+		int n_dots_;
+		int current_;
+		osg::Group *parent_;
+		osg::Node *dot_node_;
+		void AddDot(double x, double y, double z, double heading);
+
+		Trail(osg::Group *parent, osgViewer::Viewer *viewer, osg::ref_ptr<osg::Node> dot_node, osg::Vec3 color) :
+			parent_(parent), 
+			viewer_(viewer),
+			n_dots_(0), 
+			current_(0),
+			dot_node_(dot_node)
+		{
+			color_[0] = color[0];
+			color_[1] = color[1];
+			color_[2] = color[2];
+		}
+		~Trail();
+
+	private:
+		osg::Vec4 color_;
+		osgViewer::Viewer *viewer_;
+	};
+
+	class PointSensor
+	{
+	public:
+		osg::ref_ptr<osg::Group> group_;
+		osg::ref_ptr<osg::PositionAttitudeTransform> ball_;
+		double ball_radius_;
+		osg::ref_ptr<osg::Geometry> line_;
+		osg::ref_ptr<osg::Vec3Array> line_vertex_data_;
+
+		osg::Vec3 pivot_pos;
+		osg::Vec3 target_pos;
+
+		PointSensor() : line_(0), line_vertex_data_(0), ball_(0) {};
+		void Show() { group_->setNodeMask(NODE_MASK_ROAD_SENSORS); }
+		void Hide() { group_->setNodeMask(0x0); };
+	};
+
+	class EntityModel
+	{
+	public:
+
+		typedef enum {
+			ENTITY_TYPE_VEHICLE,
+			ENTITY_TYPE_OTHER
+		} EntityType;
+
+		osg::ref_ptr<osg::Group> group_;
+		osg::ref_ptr<osg::LOD> lod_;
+		osg::ref_ptr<osg::PositionAttitudeTransform> txNode_;
+		osg::ref_ptr<osg::Group> bb_;
+		osg::Quat quat_;
+		double size_x;
+		double size_y;
+		double center_x;
+		double center_y;
+		static const int entity_type_ = ENTITY_TYPE_OTHER;
+		virtual int GetType() { return entity_type_; }
+
+		std::string name_;
+		std::string filename_;
+		osg::ref_ptr<osg::BlendColor> blend_color_;
+		osg::ref_ptr<osg::StateSet> state_set_;
+
+		EntityModel(osgViewer::Viewer* viewer, osg::ref_ptr<osg::Group> group, osg::ref_ptr<osg::Group> parent, osg::ref_ptr<osg::Group> 
+			trail_parent, osg::ref_ptr<osg::Node> dot_node, osg::Vec3 trail_color, std::string name);
+		void SetPosition(double x, double y, double z);
+		void SetRotation(double h, double p, double r);
+
+		void SetTransparency(double factor);
+
+
+		Trail* trail_;
+		osgViewer::Viewer* viewer_;
+	};
+
+	class CarModel : public EntityModel
+	{
+	public:
+		std::vector<osg::ref_ptr<osg::PositionAttitudeTransform>> wheel_;
+		double wheel_angle_;
+		double wheel_rot_;
+		PointSensor* road_sensor_;
+		PointSensor* lane_sensor_;
+		PointSensor* trail_sensor_;
+		PointSensor* steering_sensor_;
+		static const int entity_type_ = ENTITY_TYPE_VEHICLE;
+		virtual int GetType() { return entity_type_; }
+
+		CarModel(osgViewer::Viewer* viewer, osg::ref_ptr<osg::Group> group, osg::ref_ptr<osg::Group> parent, osg::ref_ptr<osg::Group>
+			trail_parent, osg::ref_ptr<osg::Node> dot_node, osg::Vec3 trail_color, std::string name);
+		~CarModel();
+		osg::ref_ptr<osg::PositionAttitudeTransform>  AddWheel(osg::ref_ptr<osg::Node> carNode, const char* wheelName);
+		void UpdateWheels(double wheel_angle, double wheel_rotation);
+		void UpdateWheelsDelta(double wheel_angle, double wheel_rotation_delta);
+	};
+
+	class VisibilityCallback : public osg::NodeCallback
+	{
+	public:
+		VisibilityCallback(osg::Node* node, scenarioengine::Object* object, EntityModel* entity)
+		{
+			node_ = (osg::LOD*)node;
+			object_ = object;
+			entity_ = entity;
+		}
+		virtual void operator()(osg::Node*, osg::NodeVisitor*);
+
+	protected:
+		osg::ref_ptr<osgAnimation::InCubicMotion> _motion;
+
+	private:
+		scenarioengine::Object* object_;
+		EntityModel* entity_;
+		osg::LOD* node_;
+	};
+
+	typedef struct
+	{
+		int key_;
+		int modKeyMask_;
+		bool down_;
+	} KeyEvent;
+
+	typedef enum
+	{
+		ENTITY_HIDE,
+		ENTITY_3D_MODEL,
+		ENTITY_BOUNDINGBOX,
+		ENTITY_BOTH
+	} ENTITY_SHOW_MODE;
+
+	typedef void (*KeyEventCallbackFunc)(KeyEvent*, void*);
+
+	typedef struct
+	{
+		KeyEventCallbackFunc func;
+		void* data;
+	} KeyEventCallback;
+
+	class Viewer
+	{
+	public:
+		int currentCarInFocus_;
+		int camMode_;
+		osg::ref_ptr<osg::Group> line_node_;
+
+		// Vehicle position debug visualization
+		osg::ref_ptr<osg::Node> shadow_node_;
+
+		// Trail dot model
+		osg::ref_ptr<osg::Node> dot_node_;
+
+		// Road debug visualization
+		osg::ref_ptr<osg::Group> odrLines_;
+		osg::ref_ptr<osg::Group> osiLines_;
+		osg::ref_ptr<osg::Group> osiPoints_;
+		osg::ref_ptr<osg::PositionAttitudeTransform> envTx_;
+		osg::ref_ptr<osg::Node> environment_;
+		osg::ref_ptr<osgGA::RubberbandManipulator> rubberbandManipulator_;
+		osg::ref_ptr<osgGA::NodeTrackerManipulator> nodeTrackerManipulator_;
+		std::vector<EntityModel*> entities_;
+		float lodScale_;
+		osgViewer::Viewer *osgViewer_;
+		osg::MatrixTransform* rootnode_;
+		osg::ref_ptr<osg::Group> roadSensors_;
+		osg::ref_ptr<osg::Group> trails_;
+		roadmanager::OpenDrive *odrManager_;
+		bool showInfoText;
+		RoadGeom* roadGeom;
+
+		std::string exe_path_;
+		std::vector<KeyEventCallback> callback_;
+
+		osg::ref_ptr<osg::Camera> infoTextCamera;
+		osg::ref_ptr<osgText::Text> infoText;
+
+		Viewer(roadmanager::OpenDrive *odrManager, const char* modelFilename, const char* scenarioFilename, const char* exe_path, osg::ArgumentParser arguments, SE_Options* opt = 0);
+		~Viewer();
+		void SetCameraMode(int mode);
+		void SetVehicleInFocus(int idx);
+		int GetEntityInFocus() { return currentCarInFocus_; }
+		EntityModel* AddEntityModel(std::string modelFilepath, osg::Vec3 trail_color, EntityModel::EntityType type, 
+			bool road_sensor, std::string name, OSCBoundingBox *boundingBox);
+		void RemoveCar(std::string name);
+		int LoadShadowfile(std::string vehicleModelFilename);
+		int AddEnvironment(const char* filename);
+		osg::ref_ptr<osg::Group> LoadEntityModel(const char *filename);
+		void UpdateSensor(PointSensor *sensor);
+		void SensorSetPivotPos(PointSensor *sensor, double x, double y, double z);
+		void SensorSetTargetPos(PointSensor *sensor, double x, double y, double z);
+		void UpdateRoadSensors(PointSensor *road_sensor, PointSensor *lane_sensor, roadmanager::Position *pos);
+		void setKeyUp(bool pressed) { keyUp_ = pressed; }
+		void setKeyDown(bool pressed) { keyDown_ = pressed; }
+		void setKeyLeft(bool pressed) { keyLeft_ = pressed; }
+		void setKeyRight(bool pressed) { keyRight_ = pressed; }
+		bool getKeyUp() { return keyUp_; }
+		bool getKeyDown() { return keyDown_; }
+		bool getKeyLeft() { return keyLeft_; }
+		bool getKeyRight() { return keyRight_; }
+		void SetQuitRequest(bool value) { quit_request_ = value; }
+		bool GetQuitRequest() { return quit_request_;  }
+		void SetInfoTextProjection(int width, int height);
+		void SetInfoText(const char* text);
+		void ShowInfoText(bool show);
+		void SetNodeMaskBits(int bits);
+		void SetNodeMaskBits(int mask, int bits);
+		void ClearNodeMaskBits(int bits);
+		void ToggleNodeMaskBits(int bits);
+		int GetNodeMaskBit(int mask);
+		PointSensor* CreateSensor(double color[], bool create_ball, bool create_line, double ball_radius, double line_width);
+		bool CreateRoadSensors(CarModel *vehicle_model);
+		void SetWindowTitle(std::string title);
+		void SetWindowTitleFromArgs(std::vector<std::string> &arg);
+		void SetWindowTitleFromArgs(int argc, char* argv[]);
+		void RegisterKeyEventCallback(KeyEventCallbackFunc func, void* data);
+
+	private:
+
+		bool CreateRoadLines(roadmanager::OpenDrive* od);
+		bool CreateRoadMarkLines(roadmanager::OpenDrive* od);
+		int CreateOutlineObject(roadmanager::Outline* outline);
+		int LoadRoadFeature(roadmanager::Road* road, std::string filename, double s, double t,
+			double z_offset, double scale_x, double scale_y, double scale_z, double heading_offset);
+		int CreateRoadSignsAndObjects(roadmanager::OpenDrive* od);
+		bool keyUp_;
+		bool keyDown_;
+		bool keyLeft_;
+		bool keyRight_;
+		bool quit_request_;
+	};
+
+	class ViewerEventHandler : public osgGA::GUIEventHandler
+	{
+	public:
+		ViewerEventHandler(Viewer *viewer) : viewer_(viewer) {}
+		bool handle(const osgGA::GUIEventAdapter& ea, osgGA::GUIActionAdapter&);
+
+	private:
+		Viewer* viewer_;
+	};
+}
+
+
+
+#endif  // VIEWER_HPP_
+