Procházet zdrojové kódy

add map choose function

HAPO-9# před 3 roky
rodič
revize
6fd13dbd0b

+ 2 - 0
src/driver/driver_map_xodrload/driver_map_xodrload.pro

@@ -29,11 +29,13 @@ SOURCES += main.cpp     \
     ../../include/msgtype/gps.pb.cc \
     ../../include/msgtype/gpsimu.pb.cc \
     ../../include/msgtype/imu.pb.cc \
+    ../../include/msgtype/hmi.pb.cc \
     gnss_coordinate_convert.cpp
 
 HEADERS += \
     ../../../include/ivexit.h \
     ../../include/msgtype/v2x.pb.h \
+    ../../include/msgtype/hmi.pb.h \
     mconf.h \
     globalplan.h \
     gps_type.h \

+ 21 - 6
src/driver/driver_map_xodrload/main.cpp

@@ -13,6 +13,8 @@
 
 #include "v2x.pb.h"
 
+#include "hmi.pb.h"
+
 #include "modulecomm.h"
 
 #include "xmlparam.h"
@@ -45,6 +47,7 @@ void * gpmap;
 void * gpagps;
 void * gpasimple;
 void * gpav2x;
+void * gpaHmi;
 
 iv::Ivfault *gfault = nullptr;
 iv::Ivlog *givlog = nullptr;
@@ -789,6 +792,23 @@ void ListenV2X(const char * strdata,const unsigned int nSize,const unsigned int
 
     MultiStationPlan(&xv2x,gsrc.flatsrc,gsrc.flonsrc,gsrc.fhgdsrc,1);
 }
+void ListenHmi(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    iv::hmi::hmimsg xhmimsg;
+    if(!xhmimsg.ParseFromArray(strdata,nSize))
+    {
+        givlog->warn("<map lodar> ListenHmi Parse Error.");
+        std::cout<<"<map lodar> ListenHmi Parse Error."<<std::endl;
+        return;
+    }
+    if(xhmimsg.has_mapname())
+    {
+        if(LoadXODR(xhmimsg.mapname()))
+            givlog->info("mapLoad","load map success: %s",xhmimsg.mapname());
+        else
+            givlog->error("mapLoad","load map fail: %s",xhmimsg.mapname());
+    }
+}
 
 void ListenSrc(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
 {
@@ -853,12 +873,6 @@ int main(int argc, char *argv[])
         strparapath = argv[2];
     }
 
-
-
-
-
-
-
     iv::xmlparam::Xmlparam xp(strparapath);
     xp.GetParam(std::string("he"),std::string("1"));
     std::string strlat0 = xp.GetParam("lat0","39");
@@ -897,6 +911,7 @@ int main(int argc, char *argv[])
     gpasrc =iv::modulecomm::RegisterRecv("xodrsrc",ListenSrc);
     gpagps = iv::modulecomm::RegisterRecv(strgpsmsg.data(),UpdateGPSIMU);
     gpav2x = iv::modulecomm::RegisterRecv(strv2xmsg.data(),ListenV2X);
+    gpaHmi = iv::modulecomm::RegisterRecv("hmi",ListenHmi);
 
     gpasimple = iv::modulecomm::RegisterSend("simpletrace",100000,1);
 

+ 7 - 0
src/include/proto/hmi.proto

@@ -2,6 +2,11 @@ syntax = "proto2";
 
 package iv.hmi;
 
+message stationsGPS
+{
+	required double lat		= 1;
+	required double	lon		= 2;
+};
 message hmimsg
 {
  optional bool mbPause = 1;
@@ -28,4 +33,6 @@ message hmimsg
  optional bool platformEn = 22;//云平台使能
  optional bool obuEn = 23;//路测通信使能
  optional float speedLimit = 24; //限速
+ optional string mapName = 25;
+ optional stationsGPS gps = 26; //站点坐标
 };

+ 38 - 6
src/ui/ui_ads_hmi_1px/ADCIntelligentVehicle.cpp

@@ -7,6 +7,8 @@
 
 extern std::string gstrmemgps;
 extern std::string gstrvin;
+extern std::string gstrLat;
+extern std::string gstrLon;
 /**
      常量 	值 	描述
     QHostAddress::Null 	0 	空地址对象,相当于QHostAddress()。
@@ -187,6 +189,22 @@ void ListenV2xStReq(const char * strdata,const unsigned int nSize,const unsigned
     }
 }
 
+//vbu数据处理
+void ListenObu(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+//    iv::v2x::v2xStReq xv2xStReqMsg;
+//    if(!xv2xStReqMsg.ParseFromArray(strdata,nSize))
+//    {
+//        gIvlog->error("hmi", "iv::v2x::xv2xStReqMsg::ListenV2xStReq parse error");
+//        return;
+//    }
+//    if(xv2xStReqMsg.v2xstreq())
+//    {
+//        gAV->UpdateV2xStEn(gAV->mv2xStEn);
+//        gIvlog->info("hmi", "v2x enable request %d",gAV->mv2xStEn);
+//    }
+}
+
 /**
  * @brief ADCIntelligentVehicle::ADCIntelligentVehicle
  * @param parent
@@ -345,11 +363,11 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     ModuleFun fundecition =std::bind(&ADCIntelligentVehicle::UpdateDecition,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
 
 //    mpaDecition = iv::modulecomm::RegisterRecvPlus("decition",fundecition);
-    mpaDecition = iv::modulecomm::RegisterRecvPlus("deciton",fundecition);
-
+    mpaDecition = iv::modulecomm::RegisterRecvPlus("deciton",fundecition);    
     mpaLidar = iv::modulecomm::RegisterRecv("lidar_obs",ListenOBS);
-
+    mpaObu = iv::modulecomm::RegisterRecv("obu",ListenObu);
     mpaHMI = iv::modulecomm::RegisterSend("hmi",10*sizeof(iv::hmi::HMIBasic),10);
+    mpadst = iv::modulecomm::RegisterSend("xodrreq",1000,1);//地图站点gps信息
 
     iv::modulecomm::RegisterRecv("v2xStReq", ListenV2xStReq);
     mp_v2xStSend = iv::modulecomm::RegisterSend("v2xStEn",1000,1);
@@ -430,6 +448,8 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     #endif
 
     ui->lineEdit_vin->setText(QString::fromStdString(gstrvin));
+    mdLon = QString::fromStdString(gstrLon).toDouble();
+    mdLat = QString::fromStdString(gstrLat).toDouble();
 }
 
 /**
@@ -2068,15 +2088,27 @@ void ADCIntelligentVehicle::on_button_map_set_clicked()
                                  tr("Text Files (*.xodr)"));
      if (fileName.isEmpty())
      {
-         QMessageBox msgBox(QMessageBox::Warning, tr("警告"),
+        QMessageBox msgBox(QMessageBox::Warning, tr("警告"),
                                 "No Map Selected", 0, this);
-         msgBox.addButton(tr("OK"), QMessageBox::AcceptRole);
+        msgBox.addButton(tr("OK"), QMessageBox::AcceptRole);
 //         msgBox.addButton(tr("&Continue"), QMessageBox::RejectRole);
 //         if (msgBox.exec() == QMessageBox::AcceptRole)
 //             qDebug()<<"accept";
 //         else
 //             qDebug()<<"reject";
-    }
+     }else{
+         //发送地图文件名到driver_map_xodrload
+         iv::hmi::hmimsg hmi;
+         hmi.set_mapname(fileName.toStdString());
+         ShareHMIMsgPro(hmi);
+
+         //发送站点gps信息
+         xodrobj xo;
+         xo.flon = mdLon;
+         xo.flat = mdLat;
+         xo.lane = 1;
+         iv::modulecomm::ModuleSendMsg(mpadst,(char *)&xo,sizeof(xodrobj));
+     }
 }
 
 void ADCIntelligentVehicle::on_button_vin_set_clicked()

+ 13 - 1
src/ui/ui_ads_hmi_1px/ADCIntelligentVehicle.h

@@ -343,6 +343,7 @@ private:
 
 private:
     void * mpaLidar;
+    void * mpaObu;
 
 public:
     void UpdateOBS(std::shared_ptr<std::vector<iv::ObstacleBasic> > lidar_obs);
@@ -368,7 +369,18 @@ public:
 private:
     QImage img,img2,img3,img4;
     QTimer mTimerState1;
+    double mdLat,mdLon;
+    void *mpadst;
 };
 
-
+class xodrobj
+{
+public:
+    double flatsrc;
+    double flonsrc;
+    double fhgdsrc;
+    double flat;
+    double flon;
+    int lane;
+};
 #endif

+ 7 - 1
src/ui/ui_ads_hmi_1px/ADCIntelligentVehicle.ui

@@ -110,7 +110,7 @@
      </rect>
     </property>
     <property name="currentIndex">
-     <number>1</number>
+     <number>0</number>
     </property>
     <widget class="QWidget" name="page_0">
      <widget class="QGroupBox" name="groupBox_2">
@@ -156,6 +156,12 @@
            <family>AR PL UKai CN</family>
           </font>
          </property>
+         <property name="statusTip">
+          <string/>
+         </property>
+         <property name="whatsThis">
+          <string extracomment="请在配置文件中设置终点信息"/>
+         </property>
          <property name="text">
           <string>地图设置</string>
          </property>

+ 4 - 0
src/ui/ui_ads_hmi_1px/main.cpp

@@ -16,6 +16,8 @@ std::string gstrmemdecition;
 std::string gstrmembrainstate;
 std::string gstrmemchassis;
 std::string gstrvin;
+std::string gstrLat;
+std::string gstrLon;
 
 int main(int argc, char *argv[])
 {
@@ -41,6 +43,8 @@ int main(int argc, char *argv[])
    gstrmembrainstate = xp.GetParam("brainstate","brainstate");
    gstrmemchassis = xp.GetParam("chassismsgname","chassis");
    gstrvin = xp.GetParam("vin","LMWHP1S27J1005905");
+   gstrLat = xp.GetParam("lat","0");
+   gstrLon = xp.GetParam("lon","0");
 
 #if (QT_VERSION <= QT_VERSION_CHECK(5,0,0))    //apollo_fu 20200413 添加对QT4版本的中文字体支持
     //QT5版本以上默认就是采用UTF-8编码