Browse Source

添加状态机的一部分代码

fujiankuan 3 năm trước cách đây
mục cha
commit
05a2bcbb4f

+ 12 - 0
src/decition/common/common/car_status.h

@@ -229,6 +229,18 @@ namespace iv {
         double distoParkPoint=200;
         std::vector<iv::GPS_INS> xlcParkPoint;//存放停车点经纬的vetor
          //巡逻车增加停车点位.end
+
+        //=========================apollo_fu 2022=======================
+        int guide_carState = 5;	// 0:待命停车 1:任务中	 2:返程 3:返库 4:停工停车 5:人工接管
+        bool guide_faultstate = 1;//正常1 故障0
+        bool guide_workcommand = 0;//开工1 停工0
+        bool guide_takeovercommand = 1; //进入接管1    退出接管0
+        bool guide_timeout = 0;    //超时1  未超时0
+        int guide_task = 0;   //收到任务1    完成任务2   取消任务3
+        bool guide_nearpath = 1; //靠近路线1   远离路线0
+        double guide_amilng = 0.0;
+        double guide_amilat = 0.0;
+        //==============================================================
     };
     typedef boost::serialization::singleton<iv::CarStatus> CarStatusSingleton;//非线程安全,注意多线程加锁,单例模式
 }

+ 237 - 155
src/decition/decition_brain_sf_jsguide/decition/brain.cpp

@@ -30,39 +30,39 @@ namespace decition {
 iv::decition::BrainDecition * gbrain;
 
 
-        void ListenTraceMap(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
-        {
-            gbrain->UpdateMap(strdata,nSize);
-            gbrain->UpdateSate();
-        }
+void ListenTraceMap(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    gbrain->UpdateMap(strdata,nSize);
+    gbrain->UpdateSate();
+}
 
-        void ListenVbox(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
-        {
-            gbrain->UpdateVbox(strdata,nSize);
-            gbrain->UpdateSate();
-        }
+void ListenVbox(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    gbrain->UpdateVbox(strdata,nSize);
+    gbrain->UpdateSate();
+}
 
-        void ListenHMI(const char * strdata,const unsigned int nSize ,const unsigned int index,const QDateTime * dt,const char * strmemname)
-        {
-            gbrain->UpdateHMI(strdata,nSize);
-        }
+void ListenHMI(const char * strdata,const unsigned int nSize ,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    gbrain->UpdateHMI(strdata,nSize);
+}
 
-        void ListenPlatform(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
-        {
-            gbrain->UpdatePlatform(strdata,nSize);
-        }
+void ListenPlatform(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    gbrain->UpdatePlatform(strdata,nSize);
+}
 
-        void ListenGroup(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
-        {
-            gbrain->UpdateGroupInfo(strdata,nSize);
-        }
+void ListenGroup(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    gbrain->UpdateGroupInfo(strdata,nSize);
+}
 
-        void ListenFusion(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
-        {
-           gbrain->GetFusion(strdata,nSize);
-        }
+void ListenFusion(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
+{
+    gbrain->GetFusion(strdata,nSize);
+}
 
-    /*    void ListenMap_change_req(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+/*    void ListenMap_change_req(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
         {
             iv::formation_map_index::map map;
             if(false == map.ParseFromArray(strdata,nSize))
@@ -75,7 +75,7 @@ iv::decition::BrainDecition * gbrain;
         //    map.index()-1  map index num.
         }*/
 
-    }
+}
 
 }
 
@@ -130,7 +130,7 @@ iv::decition::BrainDecition::BrainDecition()
     mpaPlatform = iv::modulecomm::RegisterRecv("platformfrom",iv::decition::ListenPlatform);
 
     mpaGroup = iv::modulecomm::RegisterRecv("p900_send",iv::decition::ListenGroup);
- //   iv::modulecomm::RegisterRecv("map_index",ListenMap_change_req);
+    //   iv::modulecomm::RegisterRecv("map_index",ListenMap_change_req);
 
 
 
@@ -152,6 +152,11 @@ iv::decition::BrainDecition::BrainDecition()
     mTime.start();
     mnOldTime = mTime.elapsed();
 
+    //============================= apollo_fu 2022 ============================
+    guide_pTimer = new QTimer();
+    guide_pTimer->setInterval(4000);//4s
+    //=========================================================================
+
 }
 
 iv::decition::BrainDecition::~BrainDecition()
@@ -292,7 +297,7 @@ void iv::decition::BrainDecition::run() {
     std::string strroadmode_vel = xp.GetParam("roadmode0","10");
     ServiceCarStatus.mroadmode_vel.mfmode0 = atof(strroadmode_vel.data());
 
-     strroadmode_vel= xp.GetParam("roadmode1","10");
+    strroadmode_vel= xp.GetParam("roadmode1","10");
     ServiceCarStatus.mroadmode_vel.mfmode1 = atof(strroadmode_vel.data());
 
     strroadmode_vel = xp.GetParam("roadmode11","30");
@@ -414,7 +419,7 @@ void iv::decition::BrainDecition::run() {
     std::string groupID = xp.GetParam("groupid","1");
     ServiceCarStatus.curID = atoi(groupID.data());
 
-     adjuseGpsLidarPosition();
+    adjuseGpsLidarPosition();
 
     if(strexternmpc == "true")
     {
@@ -507,7 +512,7 @@ void iv::decition::BrainDecition::run() {
             decition_gps->torque = 0;
             decition_gps->mode = 0;
             //decitionExecuter->executeDecition(decition_gps);
-                   ShareDecition(decition_gps);  //apollo_fu 20200413 qudiaozhushi
+            ShareDecition(decition_gps);  //apollo_fu 20200413 qudiaozhushi
             ServiceCarStatus.mfAcc = decition_gps->accelerator;
             ServiceCarStatus.mfWheel = decition_gps->wheel_angle;
             ServiceCarStatus.mfBrake = decition_gps->brake;
@@ -536,7 +541,7 @@ void iv::decition::BrainDecition::run() {
 #ifdef Q_OS_WIN32
             boost::this_thread::sleep(boost::posix_time::milliseconds(10));
 #endif
-             std::cout<<"enter mbRunPause"<<std::endl;
+            std::cout<<"enter mbRunPause"<<std::endl;
             continue;
 
         }
@@ -550,13 +555,13 @@ void iv::decition::BrainDecition::run() {
         //      gps_data_ = NULL;
 
         //        if(obs_lidar_grid_ != NULL)free(obs_lidar_grid_);
-//        if(fusion_ptr_ != NULL)
-//        {
-//            if(old_obs_lidar_grid_ != NULL) free(old_obs_lidar_grid_);
-//            old_obs_lidar_grid_ = fusion_ptr_;
-//        }
+        //        if(fusion_ptr_ != NULL)
+        //        {
+        //            if(old_obs_lidar_grid_ != NULL) free(old_obs_lidar_grid_);
+        //            old_obs_lidar_grid_ = fusion_ptr_;
+        //        }
 
-//        fusion_ptr_ = NULL;
+        //        fusion_ptr_ = NULL;
 
         if(obs_camera_ != NULL)free(obs_camera_);
 
@@ -566,7 +571,7 @@ void iv::decition::BrainDecition::run() {
 
         eyes->getSensorObstacle(obs_radar_, obs_camera_,gps_data_, obs_lidar_grid_);	//从传感器线程临界区交换数据
 
-/*
+        /*
         if(obs_lidar_grid_!= NULL)
         {
             std::cout<<"receive fusion date"<<std::endl;
@@ -594,43 +599,43 @@ void iv::decition::BrainDecition::run() {
 
         ServiceLidar.copylidarperto(lidar_per);
 
-//                if(lidar_per->size() >0)
-//                {
-//                    int i;
-//                    for(i=0;i<lidar_per->size();i++)
-//                    {
-//                        if(lidar_per->at(i).label>0)
-//                        {
-//                            std::cout<<"label is"<<lidar_per->at(i).label<<" vy = "<<lidar_per->at(i).velocity.y<<std::endl;
-//                        }
-//                    }
-//                    //if size > 0, have perception result;
-//                }
-
-
-                if(lidar_per->empty()){
-                   miss_lidar_per_count++;
-                   miss_lidar_per_count=min(miss_lidar_per_limit,miss_lidar_per_count);
-                   if(miss_lidar_per_count<miss_lidar_per_limit && old_lidar_per!=NULL){
-                    lidar_per=old_lidar_per;
-                   }
-                }else{
-                    old_lidar_per=lidar_per;
-                    miss_lidar_per_count=0;
-                }
+        //                if(lidar_per->size() >0)
+        //                {
+        //                    int i;
+        //                    for(i=0;i<lidar_per->size();i++)
+        //                    {
+        //                        if(lidar_per->at(i).label>0)
+        //                        {
+        //                            std::cout<<"label is"<<lidar_per->at(i).label<<" vy = "<<lidar_per->at(i).velocity.y<<std::endl;
+        //                        }
+        //                    }
+        //                    //if size > 0, have perception result;
+        //                }
+
+
+        if(lidar_per->empty()){
+            miss_lidar_per_count++;
+            miss_lidar_per_count=min(miss_lidar_per_limit,miss_lidar_per_count);
+            if(miss_lidar_per_count<miss_lidar_per_limit && old_lidar_per!=NULL){
+                lidar_per=old_lidar_per;
+            }
+        }else{
+            old_lidar_per=lidar_per;
+            miss_lidar_per_count=0;
+        }
 
-//                if(lidar_per->size() >0)
-//                {
-//                    int i;
-//                    for(i=0;i<lidar_per->size();i++)
-//                    {
-//                        if(lidar_per->at(i).label>0)
-//                        {
-//                            std::cout<<"label is"<<lidar_per->at(i).label<<" vy = "<<lidar_per->at(i).velocity.y<<std::endl;
-//                        }
-//                    }
-//                    //if size > 0, have perception result;
-//                }
+        //                if(lidar_per->size() >0)
+        //                {
+        //                    int i;
+        //                    for(i=0;i<lidar_per->size();i++)
+        //                    {
+        //                        if(lidar_per->at(i).label>0)
+        //                        {
+        //                            std::cout<<"label is"<<lidar_per->at(i).label<<" vy = "<<lidar_per->at(i).velocity.y<<std::endl;
+        //                        }
+        //                    }
+        //                    //if size > 0, have perception result;
+        //                }
 
         iv::ObsLiDAR obs_lidar_tmp(new std::vector<iv::ObstacleBasic>);
         iv::ObsRadar obs_radar_tmp(new std::vector<iv::ObstacleBasic>);
@@ -697,7 +702,9 @@ void iv::decition::BrainDecition::run() {
 
 
 
-        if (gps_data_  &&!handPark && !ServiceCarStatus.m_bOutGarage){// && obs_lidar_grid_) {	//处理GPS数据
+        if (gps_data_  &&!handPark && !ServiceCarStatus.m_bOutGarage)
+        {
+            // && obs_lidar_grid_) {	//处理GPS数据
             //todo gps_data_为当前读到的gps位置信息
             //decition_gps = iv::decition::Decition(new iv::decition::DecitionBasic);
             //ODS("接收GPS数据:%f\t\t%f\n", gps_data_->gps_x, gps_data_->gps_y);
@@ -746,17 +753,17 @@ void iv::decition::BrainDecition::run() {
                 mfVehSpeedLast=ServiceCarStatus.vehSpeed_st;
             }
 
-//            iv::LidarGridPtr templidar= obs_lidar_grid_;
+            //            iv::LidarGridPtr templidar= obs_lidar_grid_;
             iv::LidarGridPtr  templidar;
             templidar = NULL;
             mMutex_.lock();
 
             if(fusion_ptr_ != NULL)
             {
-               if(old_obs_lidar_grid_ != NULL)
-               {
-                   free(old_obs_lidar_grid_);
-               }
+                if(old_obs_lidar_grid_ != NULL)
+                {
+                    free(old_obs_lidar_grid_);
+                }
                 old_obs_lidar_grid_ = fusion_ptr_;
                 templidar = fusion_ptr_;
 
@@ -764,40 +771,40 @@ void iv::decition::BrainDecition::run() {
             fusion_ptr_ = NULL;
             mMutex_.unlock();
 
-//            iv::LidarGridPtr  templidar = fusion_ptr_;
+            //            iv::LidarGridPtr  templidar = fusion_ptr_;
 
 
             if(templidar == NULL)
                 templidar = old_obs_lidar_grid_;
 
 
-        //    GaussProjCal(gps_data_->gps_lng,gps_data_->gps_lat,&gps_data_->gps_x,&gps_data_->gps_y);
+            //    GaussProjCal(gps_data_->gps_lng,gps_data_->gps_lat,&gps_data_->gps_x,&gps_data_->gps_y);
 
 
 
-//            if(templidar!= NULL)
-//            {
-//                std::cout<<"receive fusion date"<<std::endl;
-//                int i,j;
-//                for(i=0;i<iv::grx;i++)
-//                {
-//                    for(j=0;j<iv::gry;j++)
-//                    {
-//                     if(templidar[i*iv::gry+j].ob == 2){
-//                         std::cout<<"ok"<<std::endl;
-//                         if(templidar[i*iv::gry+j].id > 10)
-//                         {
-//                             int xx = templidar[i*iv::gry+j].id;
-//                             xx++;
-//                         }
-//                          std::cout<<templidar[i*iv::gry+j].id<<std::endl;
-//                     }
+            //            if(templidar!= NULL)
+            //            {
+            //                std::cout<<"receive fusion date"<<std::endl;
+            //                int i,j;
+            //                for(i=0;i<iv::grx;i++)
+            //                {
+            //                    for(j=0;j<iv::gry;j++)
+            //                    {
+            //                     if(templidar[i*iv::gry+j].ob == 2){
+            //                         std::cout<<"ok"<<std::endl;
+            //                         if(templidar[i*iv::gry+j].id > 10)
+            //                         {
+            //                             int xx = templidar[i*iv::gry+j].id;
+            //                             xx++;
+            //                         }
+            //                          std::cout<<templidar[i*iv::gry+j].id<<std::endl;
+            //                     }
 
 
-//                    }
-//                }
-//                  std::cout<<"print fusion date end"<<std::endl;
-//            }
+            //                    }
+            //                }
+            //                  std::cout<<"print fusion date end"<<std::endl;
+            //            }
 
 
 
@@ -805,8 +812,8 @@ void iv::decition::BrainDecition::run() {
 
             mMutexMap.lock();
             decition_gps = decitionGps00->getDecideFromGPS(*gps_data_, navigation_data, templidar,*lidar_per,trafficLight);  // my dicition=============================
-//            free(templidar);
-            mMutexMap.unlock();                  
+            //            free(templidar);
+            mMutexMap.unlock();
             if(mbUseExternMPC)
             {
                 fanya::GPS_INS xgpsins;
@@ -885,9 +892,9 @@ void iv::decition::BrainDecition::run() {
             //		ODS("\n决策刹车:%f\n", decition_gps->brake);
             std::cout<<ServiceCarStatus.mRunTime.elapsed()<<"ms:"<< "\n决策方向:%f\n" << decition_gps->wheel_angle << std::endl;
             std::cout<<ServiceCarStatus.mRunTime.elapsed()<<"ms:"<< "\n决策速度:%f\n" << decition_gps->speed << std::endl;
-//            double decition_period=GetTickCount()-start;
-//            givlog->debug("decition_brain","period: %f",
-//                            decition_period);
+            //            double decition_period=GetTickCount()-start;
+            //            givlog->debug("decition_brain","period: %f",
+            //                            decition_period);
             last = start;
             //decitionMaker->decideFromGPS(decition_gps, gps_data_, navigation_data);		//gps_data_为当前读到的gps位置信息  navigation_data为导航数据  decition_gps为根据前两者得出的决策速度与决策角度
             //            }
@@ -991,6 +998,81 @@ void iv::decition::BrainDecition::run() {
 
         iv::modulecomm::ModuleSendMsg(mpaToPlatform,(char*)&toplat,sizeof(iv::platform::PlatFormMsg));
         //ODS("\ngetSensor时长:%f\n", end1 - start1);
+
+        //==============================apollo_fu 2022=====================================
+
+#if 0
+        int guide_carState = 4;	// 0:待命停车 1:任务中	 2:返程 3:返库 4:停工停车 5:人工接管
+        bool guide_faultstate = 1;//正常1 故障0
+        bool guide_workcommand = 0;//开工1 停工0
+        bool guide_takeovercommand = 1; //进入接管1    退出接管0
+        bool guide_timeout = 0;    //超时1  未超时0
+        int guide_task = 0;   //收到任务1    完成任务2   取消任务3
+        double guide_amilng = 0.0;
+        double guide_amilat = 0.0;
+
+#endif
+        switch (ServiceCarStatus.guide_carState) {
+        case 0:
+            if(ServiceCarStatus.guide_task == 1)
+            {
+                ServiceCarStatus.guide_carState = 1;
+            }
+            if(ServiceCarStatus.guide_timeout == 1)
+            {
+                ServiceCarStatus.guide_carState = 2;
+            }
+            if(ServiceCarStatus.guide_workcommand == 0)
+            {
+                ServiceCarStatus.guide_carState = 3;
+            }
+            if(ServiceCarStatus.guide_faultstate == 0)
+            {
+                ServiceCarStatus.guide_carState = 4;
+            }
+            if(ServiceCarStatus.guide_takeovercommand == 0)
+            {
+                ServiceCarStatus.guide_carState = 5;
+            }
+            break;
+        case 1:
+            if(ServiceCarStatus.guide_task == 2 || ServiceCarStatus.guide_task == 3)
+            {
+                ServiceCarStatus.guide_carState = 0;
+            }
+            if(ServiceCarStatus.guide_workcommand == 0)
+            {
+                ServiceCarStatus.guide_carState = 3;
+            }
+            if(ServiceCarStatus.guide_faultstate == 0)
+            {
+                ServiceCarStatus.guide_carState = 4;
+            }
+            if(ServiceCarStatus.guide_takeovercommand == 0)
+            {
+                ServiceCarStatus.guide_carState = 5;
+            }
+            break;
+        case 2:
+            if(0)  //需要添加 到达初始待命位置
+            {
+                ServiceCarStatus.guide_carState = 0;
+            }
+            break;
+        case 3:
+
+            break;
+        case 4:
+
+            break;
+        case 5:
+
+            break;
+        default:
+            break;
+        }
+        //==================================================================================
+
     }
     std::cout << "\n\n\n\n\n\n\n\n\n\n\nbrain线程退出\n" << std::endl;
 }
@@ -1205,10 +1287,10 @@ void iv::decition::BrainDecition::UpdateMap(const char *mapdata, const int mapda
             *data = x;
             navigation_data.push_back(data);
 
-   //         if(data->mode2 > 0)
-     //       {
-      //          int a = 1;
-       //     }
+            //         if(data->mode2 > 0)
+            //       {
+            //          int a = 1;
+            //     }
 
             fanya::MAP_DATA xmapdata;
             xmapdata.gps_lat = x.gps_lat;
@@ -1219,10 +1301,10 @@ void iv::decition::BrainDecition::UpdateMap(const char *mapdata, const int mapda
 
         mmpcapi.SetMAP(xvectorMAP);
 
-//        if(ServiceCarStatus.speed_control==true){
-//        Compute00().getDesiredSpeed(navigation_data);
-//            Compute00().getPlanSpeed(navigation_data);
-//        }
+        //        if(ServiceCarStatus.speed_control==true){
+        //        Compute00().getDesiredSpeed(navigation_data);
+        //            Compute00().getPlanSpeed(navigation_data);
+        //        }
         mMutexMap.unlock();
         //        mpasd->SaveState("map",mapdata,mapdatasize);
     }
@@ -1250,36 +1332,36 @@ void iv::decition::BrainDecition::ShareDecition(iv::decition::Decition decition)
     xdecition.set_engine(decition->engine);
     xdecition.set_brakelamp(decition->brakeLight);
     xdecition.set_ttc(ServiceCarStatus.mfttc);
-//    xdecition.set_air_enable(decition->air_enable);
-//    xdecition.set_air_temp(decition->air_temp);
-//    xdecition.set_air_mode(decition->air_mode);
-//    xdecition.set_wind_level(decition->wind_level);
+    //    xdecition.set_air_enable(decition->air_enable);
+    //    xdecition.set_air_temp(decition->air_temp);
+    //    xdecition.set_air_mode(decition->air_mode);
+    //    xdecition.set_wind_level(decition->wind_level);
     xdecition.set_roof_light(decition->roof_light);
     xdecition.set_home_light(decition->home_light);
-//    xdecition.set_air_worktime(decition->air_worktime);
-//    xdecition.set_air_offtime(decition->air_offtime);
-//    xdecition.set_air_on(decition->air_on);
+    //    xdecition.set_air_worktime(decition->air_worktime);
+    //    xdecition.set_air_offtime(decition->air_offtime);
+    //    xdecition.set_air_on(decition->air_on);
     xdecition.set_door(decition->door);
     xdecition.set_dippedlight(decition->nearLight);
 
     std::cout<<"===================shareDecition========================"<<std::endl;
-         std::cout<<"  torque_st:"<<ServiceCarStatus.torque_st
-                 <<"  decideTorque:"<<decition->torque <<"  decideBrake:"<<decition->brake
-                <<"  decition mode:"<<decition->mode
-        <<std::endl;
+    std::cout<<"  torque_st:"<<ServiceCarStatus.torque_st
+            <<"  decideTorque:"<<decition->torque <<"  decideBrake:"<<decition->brake
+           <<"  decition mode:"<<decition->mode
+          <<std::endl;
     std::cout<<"========================================="<<std::endl;
 
-//    givlog->verbose("torque_st: %ld",ServiceCarStatus.torque_st);
-//     givlog->verbose("decideTorque: %ld",decition->torque);
-//     givlog->verbose("decideBrake: %ld", decition->brake);
-//     givlog->debug("wheelAng: %f",decition->wheel_angle);
+    //    givlog->verbose("torque_st: %ld",ServiceCarStatus.torque_st);
+    //     givlog->verbose("decideTorque: %ld",decition->torque);
+    //     givlog->verbose("decideBrake: %ld", decition->brake);
+    //     givlog->debug("wheelAng: %f",decition->wheel_angle);
 
-   //  xdecition.set_wheelangle(100);
+    //  xdecition.set_wheelangle(100);
     static qint64 oldtime;
 
     if((QDateTime::currentMSecsSinceEpoch() - oldtime)>100)
     {
-//        givlog->warn("brain interval is more than 100ms.  value is %ld",QDateTime::currentMSecsSinceEpoch() - oldtime);
+        //        givlog->warn("brain interval is more than 100ms.  value is %ld",QDateTime::currentMSecsSinceEpoch() - oldtime);
     }
 
     //givlog->verbose("decition time is %ld",QDateTime::currentMSecsSinceEpoch());
@@ -1287,7 +1369,7 @@ void iv::decition::BrainDecition::ShareDecition(iv::decition::Decition decition)
 
 
     //givlog->verbose("torque %f wheel %f dangwei %d ",decition->torque,
-                    //decition->wheel_angle,decition->dangWei);
+    //decition->wheel_angle,decition->dangWei);
     int nsize = xdecition.ByteSize();
     char * str = new char[nsize];
     std::shared_ptr<char> pstr;
@@ -1354,7 +1436,7 @@ void iv::decition::BrainDecition::UpdateHMI(const char *pdata, const int ndatasi
     ServiceCarStatus.mbRunPause = xhmimsg.mbpause();
 
     if(xhmimsg.mbbochemode()){
-         ServiceCarStatus.bocheMode = true;
+        ServiceCarStatus.bocheMode = true;
     }
     ServiceCarStatus.busmode = xhmimsg.mbbusmode();
 
@@ -1381,7 +1463,7 @@ void iv::decition::BrainDecition::UpdateHMI(const char *pdata, const int ndatasi
     }
 
     givlog->debug("decition_brain_bool","mbdoor: %d,mbjinguang: %d",
-                    ServiceCarStatus.mbdoor,ServiceCarStatus.mbjinguang);
+                  ServiceCarStatus.mbdoor,ServiceCarStatus.mbjinguang);
 
 
 }
@@ -1450,7 +1532,7 @@ void iv::decition::BrainDecition::UpdateChassis(const char *strdata, const unsig
     }
     if(xchassis.has_torque())
     {
-         ServiceCarStatus.torque_st = xchassis.torque();
+        ServiceCarStatus.torque_st = xchassis.torque();
         if(ServiceCarStatus.msysparam.mvehtype=="bus"){
             ServiceCarStatus.torque_st = xchassis.torque()*0.4;
         }
@@ -1461,9 +1543,9 @@ void iv::decition::BrainDecition::UpdateChassis(const char *strdata, const unsig
 
     if(xchassis.has_engine_speed())
     {
-         ServiceCarStatus.engine_speed = xchassis.engine_speed();
+        ServiceCarStatus.engine_speed = xchassis.engine_speed();
 
-         std::cout<<"******* xchassis.engine_speed:"<< xchassis.engine_speed()<<std::endl;
+        std::cout<<"******* xchassis.engine_speed:"<< xchassis.engine_speed()<<std::endl;
 
 
     }
@@ -1539,16 +1621,16 @@ void iv::decition::BrainDecition::UpdateFusion(std::shared_ptr<iv::fusion::fusio
                 fusion_ptr_[dx*(iv::gry) + dy].pointcount = 5;
                 fusion_ptr_[dx*(iv::gry) + dy].ob = 2;
 
-//                if(xobs.centroid().y() < 50 && xobs.centroid().y() >5 )
-//                {
-//                    std::cout<<"     x       y    vy "<<xobs.centroid().x() <<  "     "
-//                            << xobs.centroid().y()<< "     "<<fusion_ptr_[dx*(iv::gry) + dy].speed_y<< "     "
-//                            <<xobs.vel_relative().y()<<std::endl;
-//                    givlog->debug("brain_decition","SendobsDistance: %f,SendobsSpeed: %f,objwidth: %f,nsize: %f,objsize: %f",
-//                                  xobs.centroid().y(),fusion_ptr_[dx*(iv::gry) + dy].speed_y,xobs.dimensions().x(),
-//                            xobs.nomal_centroid().size(),mfusion_obs_->obj_size());
+                //                if(xobs.centroid().y() < 50 && xobs.centroid().y() >5 )
+                //                {
+                //                    std::cout<<"     x       y    vy "<<xobs.centroid().x() <<  "     "
+                //                            << xobs.centroid().y()<< "     "<<fusion_ptr_[dx*(iv::gry) + dy].speed_y<< "     "
+                //                            <<xobs.vel_relative().y()<<std::endl;
+                //                    givlog->debug("brain_decition","SendobsDistance: %f,SendobsSpeed: %f,objwidth: %f,nsize: %f,objsize: %f",
+                //                                  xobs.centroid().y(),fusion_ptr_[dx*(iv::gry) + dy].speed_y,xobs.dimensions().x(),
+                //                            xobs.nomal_centroid().size(),mfusion_obs_->obj_size());
 
-//                }
+                //                }
             }
         }
 
@@ -1588,10 +1670,10 @@ void iv::decition::BrainDecition::UpdateVbox(const char *pdata, const int ndatas
         return;
     }
 
-//  解析box信息
-//    ServiceCarStatus.group_server_status = group_message.server_status();
-//    ServiceCarStatus.group_comm_speed= (float)group_message.car_control_speed();
-//    ServiceCarStatus.group_state= group_message.cmd_mode();
+    //  解析box信息
+    //    ServiceCarStatus.group_server_status = group_message.server_status();
+    //    ServiceCarStatus.group_comm_speed= (float)group_message.car_control_speed();
+    //    ServiceCarStatus.group_state= group_message.cmd_mode();
 
 
     trafficLight.leftColor=group_message.st_left();
@@ -1608,7 +1690,7 @@ void iv::decition::BrainDecition::UpdateVbox(const char *pdata, const int ndatas
 }
 
 void iv::decition::BrainDecition::UpdateSate(){
-     decitionGps00->isFirstRun=true;
+    decitionGps00->isFirstRun=true;
 }
 
 void iv::decition::BrainDecition::adjuseGpsLidarPosition(){

+ 5 - 0
src/decition/decition_brain_sf_jsguide/decition/brain.h

@@ -190,6 +190,11 @@ namespace iv {
             fanyaapi mmpcapi;
 
             bool mbUseExternMPC = false;
+
+            //============================= apollo_fu 2022 ============================
+            QTimer *guide_pTimer; //定时器
+
+            //=========================================================================
         };
 
     }

+ 104 - 0
src/decition/decition_brain_sf_jsguide/decition_brain_sf_jsguide.pro

@@ -0,0 +1,104 @@
+QT -= gui
+
+QT += network dbus xml
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which as 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
+
+QMAKE_LFLAGS += -no-pie
+
+# 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.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += $$PWD/../common/main.cpp \
+    ../../include/msgtype/brainstate.pb.cc \
+    ../../include/msgtype/decition.pb.cc \
+    ../../include/msgtype/radarobjectarray.pb.cc \
+    ../../include/msgtype/radarobject.pb.cc \
+    ../../include/msgtype/gpsimu.pb.cc \
+    ../../include/msgtype/mapreq.pb.cc \
+    ../../include/msgtype/hmi.pb.cc \
+    ../../include/msgtype/chassis.pb.cc \
+    ../../include/msgtype/vbox.pb.cc \
+    ../../include/msgtype/radio_send.pb.cc \
+    ../../include/msgtype/formation_map.pb.cc \
+    ../../include/msgtype/fusionobjectarray.pb.cc \
+    ../../include/msgtype/fusionobject.pb.cc \
+    ../../include/msgtype/carstate.pb.cc \
+    ../../include/msgtype/groupmsg.pb.cc \
+    ../../include/msgtype/remotectrl.pb.cc
+
+
+include($$PWD/../common/common/common.pri)
+include($$PWD/decition/decition.pri)
+include($$PWD/../common/perception_sf/perception_sf.pri)
+#include(platform/platform.pri)
+
+
+INCLUDEPATH += $$PWD/../common
+
+
+
+INCLUDEPATH += $$PWD/../../include/msgtype
+
+LIBS += -lprotobuf
+
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+#INCLUDEPATH += $$PWD/../../../include/
+#LIBS += -L$$PWD/../../../bin/ -lxmlparam -lmodulecomm -livlog
+# -livbacktrace
+
+
+
+#win32: INCLUDEPATH += C:/File/PCL_1.8/PCL_1.8.1/3rdParty/boost-1.65/include/boost-1_65
+
+win32: INCLUDEPATH += C:/File/boost/boost_1_67_0
+win32: LIBS += -LC:/File/boost/boost_1_67_0/vc2017/lib -lboost_system-vc141-mt-x64-1_67 -lboost_thread-vc141-mt-x64-1_67
+
+
+unix:LIBS += -lboost_thread -lboost_system -lboost_serialization
+unix:INCLUDEPATH += /usr/include/eigen3
+
+unix:!macx: INCLUDEPATH += $$PWD/.
+unix:!macx: DEPENDPATH += $$PWD/.
+
+HEADERS += \
+    ../../include/msgtype/brainstate.pb.h \
+    ../../include/msgtype/decition.pb.h \
+    ../../include/msgtype/radarobjectarray.pb.h \
+    ../../include/msgtype/radarobject.pb.h \
+    ../../include/msgtype/gpsimu.pb.h \
+    ../../include/msgtype/mapreq.pb.h \
+    ../../include/msgtype/hmi.pb.h \
+    ../../include/msgtype/vbox.pb.h \
+    ../common/common/roadmode_type.h \
+    ../../include/msgtype/chassis.pb.h \
+    ../../include/msgtype/radio_send.pb.h \
+    ../../include/msgtype/formation_map.pb.h \
+    ../../include/msgtype/fusionobjectarray.pb.h \
+    ../../include/msgtype/fusionobject.pb.h \
+    ../common/perception_sf/eyes.h \
+    ../common/perception_sf/perceptionoutput.h \
+    ../common/perception_sf/sensor.h \
+    ../common/perception_sf/sensor_camera.h \
+    ../common/perception_sf/sensor_gps.h \
+    ../common/perception_sf/sensor_lidar.h \
+    ../common/perception_sf/sensor_radar.h \
+    ../common/common/sysparam_type.h \
+    ../../include/msgtype/carstate.pb.h \
+    ../../include/msgtype/groupmsg.pb.h \
+    ../../include/msgtype/remotectrl.pb.h
+
+