Răsfoiți Sursa

change decition_brain. add use mobieye option.

yuchuli 3 ani în urmă
părinte
comite
a7b15a2519

+ 23 - 2
src/decition/decition_brain/decision/decide_gps_00.cpp

@@ -2665,8 +2665,9 @@ void iv::decition::DecideGps00::computeObsOnRoad(iv::LidarGridPtr lidarGridPtr,
     double mobieye_ttc,mobieye_obsid,mobieye_speed,mobieye_distance;
 
     double fveh_width = 2.0;
-//    MobieyeInst.GetObsFromMobieye(&gpsTrace,mobieye_distance,mobieye_speed,mobieye_ttc,mobieye_obsid,fveh_width);
-
+#ifdef USE_MOBIEYE_OBS
+    MobieyeInst.GetObsFromMobieye(&gpsTrace,mobieye_distance,mobieye_speed,mobieye_ttc,mobieye_obsid,fveh_width);
+#endif
     //   qDebug("time 2 is %d ",xTime.elapsed());
     //  esrDistance=-1;
 
@@ -2683,9 +2684,18 @@ void iv::decition::DecideGps00::computeObsOnRoad(iv::LidarGridPtr lidarGridPtr,
     if(lidarDistance<0){
         lidarDistance=500;
     }
+
+#ifdef USE_MOBIEYE_OBS
+    esrDistance = mobieye_distance;
+
+    if(esrDistance>150){
+        esrDistance=500;
+    }
+#else
     if(esrDistance>30){
         esrDistance=500;
     }
+#endif
 
 
 
@@ -2750,10 +2760,15 @@ void iv::decition::DecideGps00::computeObsOnRoad(iv::LidarGridPtr lidarGridPtr,
     {
         if (lidarDistance >= esrDistance)
         {
+#ifdef USE_MOBIEYE_OBS
+            obs = esrDistance;
+            obsSd = mobieye_speed;
+#else
             //	obsDistance = esrDistance;
             obs = esrDistance;
             //	obsSpeed = ServiceCarStatus.obs_radar[esrIndex].speed_y;
             obsSd=ServiceCarStatus.obs_radar[esrIndex].speed_y;
+#endif
         }
         else if (!ServiceCarStatus.obs_radar.empty())
         {
@@ -2776,8 +2791,14 @@ void iv::decition::DecideGps00::computeObsOnRoad(iv::LidarGridPtr lidarGridPtr,
     {
         //		obsDistance = esrDistance;
         //		obsSpeed = ServiceCarStatus.obs_radar[esrIndex].speed_y;
+
+#ifdef USE_MOBIEYE_OBS
+        obs = esrDistance;
+        obsSd = mobieye_speed;
+#else
         obs = esrDistance;
         obsSd = ServiceCarStatus.obs_radar[esrIndex].speed_y;
+#endif
     }
     else if (lidarDistance > 0)
     {

+ 2 - 0
src/decition/decition_brain/decition_brain.pro

@@ -11,6 +11,8 @@ CONFIG -= app_bundle
 # deprecated API in order to know how to port your code away from it.
 DEFINES += QT_DEPRECATED_WARNINGS
 
+#DEFINES += USE_MOBIEYE_OBS
+
 # You can also make your code fail to compile if you use 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.

+ 32 - 0
src1/driver/common/basecan.cpp

@@ -0,0 +1,32 @@
+#include "basecan.h"
+
+basecan::basecan()
+{
+
+}
+
+basecan::~basecan()
+{
+    qDebug(" del basecan");
+}
+
+int basecan::GetMessage(const int nch,basecan_msg *pMsg, const int nCap)
+{
+    return 0;
+}
+
+int basecan::SetMessage(const int nch, basecan_msg *pMsg)
+{
+    return 0;
+}
+
+
+void basecan::startdev()
+{
+
+}
+
+void basecan::stopdev()
+{
+
+}

+ 40 - 0
src1/driver/common/basecan.h

@@ -0,0 +1,40 @@
+#ifndef BASECAN_H
+#define BASECAN_H
+
+#include <QThread>
+
+#include "ivfault.h"
+#include "ivlog.h"
+
+class basecan_msg
+{
+  public:
+    unsigned int id;
+    bool isExtern;
+    bool isRemote;
+    unsigned char nLen;
+    unsigned char data[8];
+};
+
+class basecan : public QThread
+{
+    Q_OBJECT
+public:
+    basecan();
+    ~basecan();
+    virtual int GetMessage(const int nch,basecan_msg * pMsg,const int nCap);
+    virtual int SetMessage(const int nch,basecan_msg * pMsg); //Send Message
+
+    virtual void startdev();
+    virtual void stopdev();
+
+    virtual   bool IsOpen() = 0;
+
+    iv::Ivfault *mfault = nullptr;
+    iv::Ivlog *mivlog = nullptr;
+signals:
+    void SIG_CANOPENSTATE(bool bCAN,int nR,const char * strres);
+    void SIGTEST();
+};
+
+#endif // BASECAN_H

+ 73 - 0
src1/driver/driver_can_nvidia_agx/.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
+

+ 37 - 0
src1/driver/driver_can_nvidia_agx/driver_can_nvidia_agx.pro

@@ -0,0 +1,37 @@
+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 += \
+        ivdriver_can_nvidia_agx.cpp \
+        main.cpp \
+        nvcan.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/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}
+
+!include(../interface/ivcan.pri ) {
+    error( "Couldn't find the ivcan.pri file!" )
+}
+
+HEADERS += \
+    ivdriver_can_nvidia_agx.h \
+    nvcan.h

+ 231 - 0
src1/driver/driver_can_nvidia_agx/ivdriver_can_nvidia_agx.cpp

@@ -0,0 +1,231 @@
+#include "ivdriver_can_nvidia_agx.h"
+
+
+iv::ivdriver_can_nvidia_agx * gc;
+iv::canstate::canstate proCanSt;
+void Listencansend0(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    iv::can::canmsg msg;
+
+    if(false == msg.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"Listencansend Parse fail."<<std::endl;
+        return;
+    }
+
+    gc->sendmsg(0,msg);
+
+}
+
+void Listencansend1(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    iv::can::canmsg msg;
+
+    if(false == msg.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"Listencansend Parse fail."<<std::endl;
+        return;
+    }
+
+    gc->sendmsg(1,msg);
+
+}
+
+namespace iv {
+
+
+ivdriver_can_nvidia_agx::ivdriver_can_nvidia_agx(std::string strxmlpath)
+{
+    gc = this;
+
+    iv::xmlparam::Xmlparam xp(strxmlpath);
+
+    std::string strmemsend0 = xp.GetParam("cansend0_agx","cansend0");
+    std::string strmemsend1 = xp.GetParam("cansend1_agx","cansend1");
+    std::string strmemrecv0 = xp.GetParam("canrecv0_agx","canrecv0");
+    std::string strmemrecv1 = xp.GetParam("canrecv1_agx","canrecv1");
+
+//    std::string strmemrecv0,strmemrecv1,strmemsend0,strmemsend1;
+
+    mparecv0 = iv::modulecomm::RegisterSend(strmemrecv0.data(),100000,3);
+    mparecv1 = iv::modulecomm::RegisterSend(strmemrecv1.data(),100000,3);
+    mpcanState = iv::modulecomm::RegisterSend("canstate",18,3);
+
+    mpasend0 = iv::modulecomm::RegisterRecv(strmemsend0.data(),Listencansend0);
+    mpasend1 = iv::modulecomm::RegisterRecv(strmemsend1.data(),Listencansend1);
+
+    mpcan = new nvcan();
+    mspcan.reset(mpcan);
+ //   connect(mpcan,SIGNAL(SIG_CANOPENSTATE(bool,int,const char*)),this,SLOT(onCANState(bool,int,const char*)));
+    mpcan->startdev();
+}
+
+void ivdriver_can_nvidia_agx::sendmsg(int index, iv::can::canmsg xmsg)
+{
+    if((index <0)||(index > 1))
+    {
+        mpcan->mfault->SetFaultState(1, 0, "sendmsg index error");
+        mpcan->mivlog->error("sendmsg index err");
+        std::cout<<"canctrl::sendmsg index error"<<std::endl;
+        return;
+    }
+
+    std::vector<basecan_msg> * psendmsgvector;
+    QMutex * pMutex;
+    if(index == 0)
+    {
+        pMutex = &mMutexcan1;
+        psendmsgvector = &msendmsgvector1;
+    }
+    if(index == 1)
+    {
+        pMutex = &mMutexcan2;
+        psendmsgvector = &msendmsgvector2;
+    }
+
+    if(psendmsgvector->size() > SENDMSGBUFSIZE)
+    {
+        mpcan->mivlog->warn("sendmsg buf full");
+        return;
+    }
+
+
+    pMutex->lock();
+    if(psendmsgvector->size() > 1000)psendmsgvector->clear();
+    int i;
+    for(i=0;i<xmsg.rawmsg_size();i++)
+    {
+        basecan_msg sendmsg;
+        iv::can::canraw x;
+        x.CopyFrom(xmsg.rawmsg(i));
+        sendmsg.id = x.id();
+        sendmsg.isExtern = x.bext();
+        sendmsg.isRemote = x.bremote();
+        int nlen = x.len();
+
+        if((nlen < 0) || (nlen > 8))
+        {
+            nlen = 0;
+            mpcan->mivlog->error("sendmsg nlen err");
+            mpcan->mfault->SetFaultState(1, 0, "sendmsg nlen err");
+        }
+        sendmsg.nLen = nlen;
+        if(sendmsg.nLen > 0)
+        {
+            memcpy(sendmsg.data,x.data().data(),sendmsg.nLen);
+        }
+
+        psendmsgvector->push_back(sendmsg);
+    }
+    pMutex->unlock();
+
+
+}
+
+void ivdriver_can_nvidia_agx::modulerun()
+{
+    QTime xTime;
+    xTime.start();
+    int nOldTime = xTime.elapsed();
+    int i;
+
+    while(mbrun)
+    {
+        if(mpcan->IsOpen())
+        {
+            basecan_msg xmsg[2500];
+            int nRec1,nRec2,nSend1,nSend2;
+            if((nRec1 =mpcan->GetMessage(0,xmsg,2500))>0)
+            {
+                sharecanmsg(mparecv0,xmsg,nRec1,0);
+            }
+
+            if((nRec2 =mpcan->GetMessage(1,xmsg,2500))>0)
+            {
+                sharecanmsg(mparecv1,xmsg,nRec2,1);
+            }
+
+            nSend1 = 0;
+            nSend2 = 0;
+
+            mMutexcan1.lock();
+            for(i=0;i<msendmsgvector1.size();i++)
+            {
+                mpcan->SetMessage(0,&(msendmsgvector1.at(i)));
+            }
+            msendmsgvector1.clear();
+            mMutexcan1.unlock();
+
+            mMutexcan2.lock();
+            for(i=0;i<msendmsgvector2.size();i++)
+            {
+                mpcan->SetMessage(1,&(msendmsgvector2.at(i)));
+            }
+            msendmsgvector2.clear();
+            mMutexcan2.unlock();
+
+            proCanSt.set_b_canstate(true);
+            int nsize = proCanSt.ByteSize();
+            char * strdata = new char[proCanSt.ByteSize()];
+            if(proCanSt.SerializePartialToArray(strdata,nsize))
+            {
+                iv::modulecomm::ModuleSendMsg(mpcanState,strdata,nsize);
+            }
+            std::this_thread::sleep_for(std::chrono::milliseconds(5));
+//            msleep(5);
+        }
+        else
+        {
+            proCanSt.set_b_canstate(false);
+            int nsize = proCanSt.ByteSize();
+            char * strdata = new char[proCanSt.ByteSize()];
+            if(proCanSt.SerializePartialToArray(strdata,nsize))
+            {
+                iv::modulecomm::ModuleSendMsg(mpcanState,strdata,nsize);
+            }
+            delete strdata;
+            std::this_thread::sleep_for(std::chrono::milliseconds(1));
+ //           msleep(1);
+            mpcan->mivlog->error("%s open can card fail",__func__);
+        }
+        mpcan->mfault->SetFaultState(0, 0, "ok");
+    }
+
+}
+
+void ivdriver_can_nvidia_agx::sharecanmsg(void *xpa, basecan_msg * pxmsg,int ncount,int nch)
+{
+    iv::can::canmsg xmsg;
+
+    int i;
+    for(i=0;i<ncount;i++)
+    {
+        iv::can::canraw * praw = xmsg.add_rawmsg();
+        praw->set_id(pxmsg[i].id);
+        praw->set_data(pxmsg[i].data,8);
+        praw->set_bext(pxmsg[i].isExtern);
+        praw->set_bremote(pxmsg[i].isRemote);
+        praw->set_rectime(QDateTime::currentMSecsSinceEpoch());
+        praw->set_len(pxmsg[i].nLen);
+
+    }
+    xmsg.set_channel(nch);
+
+    xmsg.set_index(mindex[nch]);
+    mindex[nch]++;
+
+    int nsize = xmsg.ByteSize();
+    char * strdata = new char[xmsg.ByteSize()];
+    if(xmsg.SerializePartialToArray(strdata,nsize))
+    {
+        iv::modulecomm::ModuleSendMsg(xpa,strdata,nsize);
+    }
+    else
+    {
+        mpcan->mivlog->error("canctrl::sharecanmsg serialize error");
+        mpcan->mfault->SetFaultState(1, 0, "sharecanmsg serialize error");
+    }
+    delete strdata;
+}
+
+}

+ 53 - 0
src1/driver/driver_can_nvidia_agx/ivdriver_can_nvidia_agx.h

@@ -0,0 +1,53 @@
+#ifndef IVDRIVER_CAN_NVIDIA_AGX_H
+#define IVDRIVER_CAN_NVIDIA_AGX_H
+
+#include "ivdriver_can.h"
+
+#include <QThread>
+#include <QMutex>
+#include <memory>
+#include <QTimer>
+#include <array>
+#include <vector>
+#include <iostream>
+#include "nvcan.h"
+#include "modulecomm.h"
+#include "canmsg.pb.h"
+#include "canraw.pb.h"
+#include "canstate.pb.h"
+#include "xmlparam.h"
+
+namespace  iv {
+
+
+class ivdriver_can_nvidia_agx : public ivdriver_can
+{
+public:
+    ivdriver_can_nvidia_agx(std::string strxmlpath);
+
+public:
+    virtual void modulerun();
+
+private:
+    basecan * mpcan;
+    std::shared_ptr<basecan> mspcan;
+    bool mbCANOpen = false;
+
+    std::vector<basecan_msg> msendmsgvector1;
+    std::vector<basecan_msg> msendmsgvector2;
+    const int SENDMSGBUFSIZE = 3000;
+
+    QMutex mMutexcan1;
+    QMutex mMutexcan2;
+
+    int mindex[2];
+
+    void * mpasend0, * mpasend1, * mparecv0, * mparecv1, *mpcanState;
+
+public:
+    void sendmsg(int index,iv::can::canmsg xmsg);
+    void sharecanmsg(void * xpa,basecan_msg * pxmsg,int ncount,int nch);
+};
+
+}
+#endif // IVDRIVER_CAN_NVIDIA_AGX_H

+ 22 - 0
src1/driver/driver_can_nvidia_agx/main.cpp

@@ -0,0 +1,22 @@
+#include <QCoreApplication>
+
+#include <iostream>
+#include "ivdriver_can_nvidia_agx.h"
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+
+    QString strpath = QCoreApplication::applicationDirPath();
+    if(argc < 2)
+        strpath = strpath + "/driver_can_nvidia_agx.xml";
+    else
+        strpath = argv[1];
+    std::cout<<strpath.toStdString()<<std::endl;
+
+    iv::ivmodule * pivmodule = new iv::ivdriver_can_nvidia_agx(strpath.toStdString());
+    pivmodule->start();
+
+    return a.exec();
+}

+ 313 - 0
src1/driver/driver_can_nvidia_agx/nvcan.cpp

@@ -0,0 +1,313 @@
+#include "nvcan.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdint.h>
+#include <unistd.h>
+#include <string.h>
+#include <signal.h>
+#include <ctype.h>
+#include <libgen.h>
+#include <time.h>
+#include <errno.h>
+
+#include <sys/time.h>
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <sys/uio.h>
+#include <net/if.h>
+
+
+#include <linux/can.h>
+#include <linux/can/raw.h>
+
+#include <iostream>
+
+/* for hardware timestamps - since Linux 2.6.30 */
+#ifndef SO_TIMESTAMPING
+#define SO_TIMESTAMPING 37
+#endif
+
+/* from #include <linux/net_tstamp.h> - since Linux 2.6.30 */
+#define SOF_TIMESTAMPING_SOFTWARE (1<<4)
+#define SOF_TIMESTAMPING_RX_SOFTWARE (1<<3)
+#define SOF_TIMESTAMPING_RAW_HARDWARE (1<<6)
+
+#define MAXSOCK 16    /* max. number of CAN interfaces given on the cmdline */
+#define MAXIFNAMES 30 /* size of receive name index to omit ioctls */
+#define MAXCOL 6      /* number of different colors for colorized output */
+#define ANYDEV "any"  /* name of interface to receive from any CAN interface */
+#define ANL "\r\n"    /* newline in ASC mode */
+
+#define SILENT_INI 42 /* detect user setting on commandline */
+#define SILENT_OFF 0  /* no silent mode */
+#define SILENT_ANI 1  /* silent mode with animation */
+#define SILENT_ON  2  /* silent mode (completely silent) */
+
+#include <QTime>
+
+#define BUF_SIZE 1000
+
+std::string CANNAME[] = {"can0","can1"};
+
+nvcan::nvcan()
+{
+//    qDebug("nvcan");
+//    connect(this,SIGNAL(SIG_CANOPENSTATE(bool,int,const char*)),this,SLOT(onMsg(bool,int,const char*)));
+
+    mfault = new iv::Ivfault("can_agx");
+    mivlog = new iv::Ivlog("can_agx");
+
+
+}
+
+void nvcan::run()
+{
+
+    int currmax = 2;
+    fd_set rdfs;
+    int s[MAXSOCK];
+    int ret;
+    
+    struct sockaddr_can addr;
+    char ctrlmsg[CMSG_SPACE(sizeof(struct timeval) + 3*sizeof(struct timespec) + sizeof(__u32))];
+    struct iovec iov;
+    struct msghdr msg;
+    struct canfd_frame frame;
+    int nbytes, i, maxdlen;
+    struct ifreq ifr;
+    struct timeval tv, last_tv;
+    struct timeval timeout_config = { 0, 0 }, *timeout_current = 0;
+    
+    for(i=0;i<currmax;i++)
+    {
+        s[i] = socket(PF_CAN, SOCK_RAW, CAN_RAW);
+        if (s[i] < 0) {
+            emit SIG_CANOPENSTATE(false,-1,"Create Socket Error");
+            return;
+        }
+
+        addr.can_family = AF_CAN;
+
+        memset(&ifr.ifr_name, 0, sizeof(ifr.ifr_name));
+        strncpy(ifr.ifr_name, CANNAME[i].data(), 5);
+
+        if (ioctl(s[i], SIOCGIFINDEX, &ifr) < 0) {
+            emit SIG_CANOPENSTATE(false,-2,"SIOCGIFINDEX");
+            return;
+        }
+        addr.can_ifindex = ifr.ifr_ifindex;
+
+        if (bind(s[i], (struct sockaddr *)&addr, sizeof(addr)) < 0) {
+            emit SIG_CANOPENSTATE(false,-3,"bind error");
+            return;
+        }
+    }
+
+    mbCANOpen = true;
+    mivlog->verbose("open can succesfully.");
+    emit SIG_CANOPENSTATE(true,0,"open can card successfully");
+
+    iov.iov_base = &frame;
+    msg.msg_name = &addr;
+    msg.msg_iov = &iov;
+    msg.msg_iovlen = 1;
+    msg.msg_control = &ctrlmsg;
+
+    while((!QThread::isInterruptionRequested())&&(mbCANOpen))
+    {
+        FD_ZERO(&rdfs);
+        for (i=0; i<currmax; i++)
+            FD_SET(s[i], &rdfs);
+
+        if (timeout_current)
+            *timeout_current = timeout_config;
+
+        timeout_config.tv_sec= 0;
+        timeout_config.tv_usec = 100;;
+        timeout_current = &timeout_config;
+        ret = select(s[currmax-1]+1, &rdfs, NULL, NULL, timeout_current);
+        if (ret < 0) {
+            emit SIG_CANOPENSTATE(false,-4,"select error");
+            mbCANOpen = false;
+            continue;
+        }
+
+        for (i=0; i<currmax; i++) {  /* check all CAN RAW sockets */
+
+            if (FD_ISSET(s[i], &rdfs)) {
+
+                /* these settings may be modified by recvmsg() */
+                iov.iov_len = sizeof(frame);
+                msg.msg_namelen = sizeof(addr);
+                msg.msg_controllen = sizeof(ctrlmsg);
+                msg.msg_flags = 0;
+
+                nbytes = recvmsg(s[i], &msg, 0);
+
+                if (nbytes < 0) {
+ //                   if ((errno == ENETDOWN) && !down_causes_exit) {
+                    if ((errno == ENETDOWN)) {
+                        mivlog->error("%s interface down", CANNAME[i].data());
+                        mfault->SetFaultState(1, 0, "interface down");
+                        emit SIG_CANOPENSTATE(false,-5,"can card down");
+                        fprintf(stderr, "%s: interface down\n", CANNAME[i].data());
+                        return;
+                    }
+                    continue;
+//                    perror("read");
+//                    return 1;
+                }
+
+                if ((size_t)nbytes == CAN_MTU)
+                    maxdlen = CAN_MAX_DLEN;
+                else if ((size_t)nbytes == CANFD_MTU)
+                    maxdlen = CANFD_MAX_DLEN;
+                else {
+                    mivlog->warn("read incomplete message");
+                    continue;
+                }
+
+  //              qDebug("receive msg.");
+                mMutex.lock();
+
+                basecan_msg msg;
+                msg.id = frame.can_id&0x1fffffff;
+                if((frame.can_id&0x80000000)!= 0)msg.isExtern = true;
+                else msg.isExtern = false;
+                if((frame.can_id&0x40000000)!= 0)msg.isRemote = true;
+                else msg.isRemote = false;
+                msg.nLen = frame.len;
+                if((frame.len<9)&&(frame.len>0))memcpy(msg.data,frame.data,frame.len);
+                if(mMsgRecvBuf[i].size()<BUF_SIZE)
+                {
+                    mMsgRecvBuf[i].push_back(msg);
+                }
+
+                mMutex.unlock();
+
+            }
+        }
+
+        struct canfd_frame framesend[2500];
+
+        for(int nch =0;nch<currmax;nch++)
+        {
+            int nsend = 0;
+            mMutex.lock();
+            for(i=0;i<mMsgSendBuf[nch].size();i++)
+            {
+                if(i>=2500)break;
+                memcpy(framesend[i].data,mMsgSendBuf[nch].at(i).data,8);
+                framesend[i].can_id = mMsgSendBuf[nch].at(i).id;
+                if(mMsgSendBuf[nch].at(i).isExtern)
+                {
+                    framesend[i].can_id = framesend[i].can_id|0x80000000;
+                }
+                else
+                {
+                    framesend[i].can_id = framesend[i].can_id&0x7ff;
+                }
+                if(mMsgSendBuf[nch].at(i).isRemote)
+                {
+                    framesend[i].can_id= framesend[i].can_id|0x40000000;
+                }
+
+                framesend[i].len = mMsgSendBuf[nch].at(i).nLen;
+
+                nsend++;
+            }
+            mMsgSendBuf[nch].clear();
+            mMutex.unlock();
+            if(nsend > 0)
+            {
+                for(i=0;i<nsend;i++)
+                if (write(s[nch], &framesend[i],16) != 16) {
+                    mivlog->error("write error 1");
+                    perror("write error 1.");
+                    continue;
+                }
+            }
+
+        }
+
+    }
+
+    for (i=0; i<currmax; i++)
+    {
+        close(s[i]);
+    }
+}
+
+void nvcan::startdev()
+{
+    start();
+}
+
+void nvcan::stopdev()
+{
+    requestInterruption();
+    QTime xTime;
+    xTime.start();
+    while(xTime.elapsed()<100)
+    {
+        if(mbRunning == false)
+        {
+            mfault->SetFaultState(1, 0, "can closed");
+            mivlog->error("can is closed at %d",xTime.elapsed());
+            break;
+        }
+    }
+}
+
+int nvcan::GetMessage(const int nch,basecan_msg *pMsg, const int nCap)
+{
+    if((nch>1)||(nch < 0))return -1;
+    if(mMsgRecvBuf[nch].size() == 0)return 0;
+
+    int nRtn;
+    nRtn = nCap;
+    mMutex.lock();
+    if(nRtn > mMsgRecvBuf[nch].size())nRtn = mMsgRecvBuf[nch].size();
+    int i;
+    for(i=0;i<nRtn;i++)
+    {
+        memcpy(&pMsg[i],&(mMsgRecvBuf[nch].at(i)),sizeof(basecan_msg));
+    }
+
+    std::vector<basecan_msg>::iterator iter;
+    iter = mMsgRecvBuf[nch].begin();
+    for(i=0;i<nRtn;i++)
+    {
+        iter = mMsgRecvBuf[nch].erase(iter);
+    }
+
+    mMutex.unlock();
+
+    return nRtn;
+
+}
+
+int nvcan::SetMessage(const int nch, basecan_msg *pMsg)
+{
+    if((nch>1)||(nch < 0))return -1;
+
+    if(mMsgSendBuf[nch].size() > BUF_SIZE)return -2;
+
+    mMutex.lock();
+    mMsgSendBuf[nch].push_back(*pMsg);
+    mMutex.unlock();
+    return 0;
+}
+
+void nvcan::onMsg(bool bCAN, int nR, const char *strres)
+{
+    mivlog->verbose("msg is %s ",strres);
+}
+
+bool nvcan::IsOpen()
+{
+    return mbCANOpen;
+}
+

+ 40 - 0
src1/driver/driver_can_nvidia_agx/nvcan.h

@@ -0,0 +1,40 @@
+#ifndef NVCAN_H
+#define NVCAN_H
+#include "basecan.h"
+
+#include <vector>
+#include <QMutex>
+
+#include <thread>
+
+class nvcan : public basecan
+{
+    Q_OBJECT
+public:
+    nvcan();
+public:
+    void startdev();
+    void stopdev();
+
+    int GetMessage(const int nch,basecan_msg * pMsg,const int nCap);
+    int SetMessage(const int nch,basecan_msg * pMsg);
+
+    virtual   bool IsOpen();
+
+private slots:
+    void onMsg(bool bCAN,int nR,const char * strres);
+
+private:
+    void run();
+    std::vector<basecan_msg> mMsgRecvBuf[2];
+
+    std::vector<basecan_msg> mMsgSendBuf[2];
+
+    QMutex mMutex;
+
+    bool mbCANOpen = false;
+    bool mbRunning = false;
+    int mnDevNum;
+};
+
+#endif // NVCAN_H

+ 1 - 0
src1/driver/driver_gps_hcp2/driver_gps_hcp2.pro

@@ -36,3 +36,4 @@ else: unix:!android: target.path = /opt/$${TARGET}/bin
 
 HEADERS += \
     ivdriver_gps_hcp2.h
+

+ 1 - 1
src1/driver/driver_gps_hcp2/main.cpp

@@ -1,6 +1,6 @@
 #include <QCoreApplication>
 
-
+#include <iostream>
 #include "ivdriver_gps_hcp2.h"
 
 int main(int argc, char *argv[])

+ 11 - 0
src1/driver/interface/ivdriver_can.cpp

@@ -0,0 +1,11 @@
+#include "ivdriver_can.h"
+
+namespace  iv {
+
+
+ivdriver_can::ivdriver_can()
+{
+
+}
+
+}

+ 16 - 0
src1/driver/interface/ivdriver_can.h

@@ -0,0 +1,16 @@
+#ifndef IVDRIVER_CAN_H
+#define IVDRIVER_CAN_H
+
+#include "ivdriver.h"
+namespace  iv {
+
+
+class ivdriver_can : public ivdriver
+{
+public:
+    ivdriver_can();
+};
+
+}
+
+#endif // IVDRIVER_CAN_H

+ 1 - 0
src1/driver/interface/ivdriver_gps.cpp

@@ -97,6 +97,7 @@ void ivdriver_gps::broadcastmsg(gps::gpsimu &xgpsimu)
 
 void ivdriver_gps::modulerun()
 {
+
     std::cout<<"register msg name is "<<mstrmsgname<<std::endl;
     mpagpsimu = iv::modulecomm::RegisterSend(mstrmsgname.data(),10000,1);
 

+ 4 - 1
src1/interface/ivmodule.cpp

@@ -1,13 +1,13 @@
 #include "ivmodule.h"
 
 #include <string.h>
+#include <iostream>
 
 namespace iv {
 
 
 ivmodule::ivmodule()
 {
-
 }
 
 ivmodule::~ivmodule()
@@ -42,4 +42,7 @@ iv::modulecomm::ModuleComm_TYPE ivmodule::getdefefaultcommtype()
     return mdefcommtype;
 }
 
+
+
 }
+

+ 3 - 0
src1/interface/ivmodule.h

@@ -19,6 +19,9 @@ public:
     void setmodulename(const char * strmodulename);
     void setdefaultcommtype(iv::modulecomm::ModuleComm_TYPE xtype);
     iv::modulecomm::ModuleComm_TYPE getdefefaultcommtype();
+
+public:
+
 public:
     bool mbrun = true;
 private: