Browse Source

修复git,添加沿触发逻辑进行系统激活

fujiankuan 2 years ago
parent
commit
141a7b6c0c

+ 73 - 27
src/controller/controller_changan_shenlan/main.cpp

@@ -115,9 +115,13 @@ ECU_24B_t _m24B = {0,0,0,0,0,0,0,0,0,0,0};
 ECU_36E_t _m36E = {0};
 
 
-void executeDecition(const iv::brain::decition decition)
+void executeDecition(const iv::brain::decition &decition)
 {
-    //    std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
+     std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
+     std::cout<<"angle_mode is "<<decition.angle_mode()<<" angle_active is "<<decition.angle_active()<<std::endl;
+     std::cout<<"brake_type is "<<decition.brake_type()<<" acc_active is "<<decition.acc_active()<<std::endl;
+     std::cout<<"brake is "<<decition.brake()<<" brake_active is "<<decition.brake_active()<<std::endl;
+     std::cout<<"auto_mode is "<<decition.auto_mode()<<" rightlamp is "<<decition.rightlamp()<<std::endl;
     _m144.ACC_LatAngReq = ECU_144_ACC_LatAngReq_toS(decition.wheelangle());
     _m144.ADS_Reqmode = decition.angle_mode();
     _m144.ACC_MotorTorqueMaxLimitRequest = ECU_144_ACC_MotorTorqueMaxLimitRequest_toS(10);
@@ -133,15 +137,15 @@ void executeDecition(const iv::brain::decition decition)
     byte_144[5] |= ((_m144.ACC_ADCReqType & (0x03U)) << 6);
 
     /*制动过程用的减速度,加速用扭矩*/
-    _m24B.ACC_AccTrqReq = decition.niuju_y();
+    _m24B.ACC_AccTrqReq = ECU_24B_ACC_AccTrqReq_toS(decition.torque());
     _m24B.ACC_AccTrqReqActive = decition.acc_active();
-    _m24B.ACC_ACCTargetAcceleration = decition.accelerator();
-//    _m24B.ACC_AEBTargetDeceleration = 0;
-//    _m24B.ACC_AEBVehilceHoldReq = 0;
-//    _m24B.ADCReqMode = 0;
-//    _m24B.ACC_AEBActive = 0;
-//    _m24B.ACC_Driveoff_Request = 0;
-//    _m24B.ACC_DecToStop = 0;
+    _m24B.ACC_ACCTargetAcceleration = ECU_24B_ACC_ACCTargetAcceleration_toS(decition.brake());
+    //    _m24B.ACC_AEBTargetDeceleration = 0;
+    //    _m24B.ACC_AEBVehilceHoldReq = 0;
+    //    _m24B.ADCReqMode = 0;
+    //    _m24B.ACC_AEBActive = 0;
+    //    _m24B.ACC_Driveoff_Request = 0;
+    //    _m24B.ACC_DecToStop = 0;
     _m24B.ACC_CDDActive = decition.brake_active();
     _m24B.ACC_ACCMode = decition.auto_mode();
 
@@ -199,10 +203,17 @@ void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned
         return;
     }
 
-//    if(xdecition.gear() != 4)
-//    {
-//        qDebug("not D");
-//    }
+    //    if(xdecition.gear() != 4)
+    //    {
+    //        qDebug("not D");
+    //    }
+    xdecition.set_angle_mode(2);
+    xdecition.set_angle_active(1);
+    xdecition.set_acc_active(1);
+    xdecition.set_brake_active(1);
+    xdecition.set_brake_type(1);
+    xdecition.set_auto_mode(3);
+
     if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
     oldtime = QDateTime::currentMSecsSinceEpoch();
     gMutex.lock();
@@ -215,6 +226,8 @@ void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned
 
 void ExecSend()
 {
+    static int nCount = 0;
+    nCount++;
     iv::can::canmsg xmsg;
     iv::can::canraw xraw;
     //    unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
@@ -231,22 +244,29 @@ void ExecSend()
     xmsg.set_index(gnIndex);
 
     xraw.set_id(0x24B);
-    xraw.set_data(byte_144,8);
+    xraw.set_data(byte_24B,8);
     xraw.set_bext(false);
     xraw.set_bremote(false);
     xraw.set_len(8);
-    iv::can::canraw * pxraw24B = xmsg.add_rawmsg();
-    pxraw24B->CopyFrom(xraw);
+    if(nCount%2 == 1)
+    {
+        iv::can::canraw * pxraw24B = xmsg.add_rawmsg();
+        pxraw24B->CopyFrom(xraw);
+    }
     xmsg.set_channel(0);
     xmsg.set_index(gnIndex);
 
     xraw.set_id(0x36E);
-    xraw.set_data(byte_144,8);
+    xraw.set_data(byte_36E,8);
     xraw.set_bext(false);
     xraw.set_bremote(false);
     xraw.set_len(8);
-    iv::can::canraw * pxraw36E = xmsg.add_rawmsg();
-    pxraw36E->CopyFrom(xraw);
+    if(nCount == 10)
+    {
+        iv::can::canraw * pxraw36E = xmsg.add_rawmsg();
+        pxraw36E->CopyFrom(xraw);
+        nCount = 0;
+    }
     xmsg.set_channel(0);
     xmsg.set_index(gnIndex);
 
@@ -281,6 +301,31 @@ void sendthread()
 {
     initial();
     iv::brain::decition xdecition;
+
+    for(int i = 0; i < 30; i++){
+        xdecition.set_angle_mode(0);
+        xdecition.set_angle_active(0);
+        xdecition.set_acc_active(0);
+        xdecition.set_brake_active(0);
+        xdecition.set_brake_type(0);
+        xdecition.set_auto_mode(0);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    for(int i = 0; i < 30; i++){
+        xdecition.set_angle_mode(2);
+        xdecition.set_angle_active(1);
+        xdecition.set_acc_active(1);
+        xdecition.set_brake_active(1);
+        xdecition.set_brake_type(1);
+        xdecition.set_auto_mode(3);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+
+
     while(gbSendRun)
     {
         if(gnDecitionNum <= 0)
@@ -314,15 +359,16 @@ int main(int argc, char *argv[])
         strpath = argv[1];
     std::cout<<strpath.toStdString()<<std::endl;
 
-    gdecition_def.set_accelerator(-0.5);
+//    gdecition_def.set_accelerator(-0.5);
+    gdecition_def.set_brake(-0.5);
     gdecition_def.set_rightlamp(true);
     gdecition_def.set_wheelangle(0);
-    gdecition_def.set_angle_mode(0);
-    gdecition_def.set_angle_active(0);
-    gdecition_def.set_acc_active(0);
-    gdecition_def.set_brake_active(0);
-    gdecition_def.set_brake_type(0);
-    gdecition_def.set_auto_mode(0);
+    gdecition_def.set_angle_mode(2);
+    gdecition_def.set_angle_active(1);
+    gdecition_def.set_acc_active(1);
+    gdecition_def.set_brake_active(1);
+    gdecition_def.set_brake_type(1);
+    gdecition_def.set_auto_mode(3);
 
     gTime.start();
 

+ 20 - 20
src/decition/decition_brain_sf_changan_shenlan/decition/adc_adapter/changan_shenlan_adapter.cpp

@@ -85,26 +85,26 @@ iv::decition::Decition iv::decition::ChanganShenlanAdapter::getAdapterDeciton(GP
     controlBrake=min(controlBrake,100.0f);
     controlBrake=max(controlBrake,0.0f);
 
-    //    (*decition)->brake = controlBrake;
-
-    //    (*decition)->torque= controlSpeed;
-
-    //    lastTorque=(*decition)->torque;
-    (*decition)->accelerator = 0 - controlBrake/25;
-    (*decition)->niuju_y = controlSpeed;
-    lastTorque = (*decition)->niuju_y;
-    if(controlBrake > 0)
-    {
-        (*decition)->brakeEnable = 1;
-        (*decition)->brakeType = 1;
-        (*decition)->acc_active = 0;
-    }
-    else
-    {
-        (*decition)->brakeEnable = 0;
-        (*decition)->brakeType = 0;
-        (*decition)->acc_active = 1;
-    }
+        (*decition)->brake = 0 - controlBrake/25;
+        (*decition)->torque= controlSpeed;
+        lastTorque=(*decition)->torque;
+
+//    (*decition)->accelerator = 0 - controlBrake/25;
+//    (*decition)->niuju_y = controlSpeed;
+//    lastTorque = (*decition)->niuju_y;
+
+//    if(controlBrake > 0)
+//    {
+//        (*decition)->brakeEnable = 1;
+//        (*decition)->brakeType = 1;
+//        (*decition)->acc_active = 0;
+//    }
+//    else
+//    {
+//        (*decition)->brakeEnable = 0;
+//        (*decition)->brakeType = 0;
+//        (*decition)->acc_active = 1;
+//    }
 
     //    (*decition)->grade=1;
     //    (*decition)->mode=1;

+ 7 - 0
src/decition/decition_brain_sf_changan_shenlan/decition/brain.cpp

@@ -787,6 +787,13 @@ void iv::decition::BrainDecition::ShareDecition(iv::decition::Decition decition)
     xdecition.set_door(decition->door);
     xdecition.set_dippedlight(decition->nearLight);
 
+    xdecition.set_acc_active(decition->acc_active);
+    xdecition.set_brake_active(decition->brake_active);
+    xdecition.set_brake_type(decition->brakeType);
+    xdecition.set_angle_mode(decition->angle_mode);
+    xdecition.set_angle_active(decition->angle_active);
+    xdecition.set_auto_mode(decition->auto_mode);
+
     std::cout<<"===================shareDecition========================"<<std::endl;
     std::cout<<"  torque_st:"<<ServiceCarStatus.torque_st
             <<"  decideTorque:"<<decition->torque <<"  decideBrake:"<<decition->brake

+ 3 - 0
src/decition/decition_brain_sf_changan_shenlan/decition/decide_gps_00.cpp

@@ -2238,6 +2238,9 @@ void iv::decition::DecideGps00::phaseSpeedDecition(iv::decition::Decition  decit
     }else if(ServiceCarStatus.msysparam.mvehtype=="sightseeing"){
         sightseeing_Adapter->getAdapterDeciton(gpsIns, gpsTraceNow, dSpeed, obsDis,obsSpeed,  decition->accelerator,ServiceCarStatus.mfCalAcc  ,changingDangWei, &decition);
     }
+    else if(ServiceCarStatus.msysparam.mvehtype=="shenlan"){
+        changanshenlan_Adapter->getAdapterDeciton(gpsIns, gpsTraceNow, dSpeed, obsDis,obsSpeed,  decition->accelerator,ServiceCarStatus.mfCalAcc  ,changingDangWei, &decition);
+    }
 }
 
 

+ 6 - 6
src/decition/decition_brain_sf_changan_shenlan/decition/decition_type.h

@@ -52,12 +52,12 @@ struct DecitionBasic {
     float   air_offtime ;                  //空调关闭时间
 
     float niuju_y; //纵向扭矩
-    int acc_active;  //ACC扭矩请求激活(为1激活,为0不激活),不激活后不执行扭矩请求
-    int brake_active; //ACC减速激活(为1制动激活,为0制动不激活)
-    int brake_type;  //ADC请求类型(制动时为1,其余情况为0)
-    int angle_mode;  //横向控制激活模式
-    int angle_active; //横向控制激活,和上一条同时满足才执行横向请求角度
-    int auto_mode; //3为自动控制模式
+    bool acc_active;  //ACC扭矩请求激活(为1激活,为0不激活),不激活后不执行扭矩请求
+    bool brake_active; //ACC减速激活(为1制动激活,为0制动不激活)
+    bool brake_type;  //ADC请求类型(制动时为1,其余情况为0)
+    unsigned char angle_mode;  //横向控制激活模式
+    bool angle_active; //横向控制激活,和上一条同时满足才执行横向请求角度
+    unsigned char auto_mode; //3为自动控制模式
 
 };
 typedef boost::shared_ptr<DecitionBasic> Decition;	//决策