Browse Source

在长安深蓝的自动驾驶车辆上添加了沿触发的逻辑,使用的时候需要先开controller,然后开brain

Gogs 2 years ago
parent
commit
1f36bfcb10

+ 14 - 130
src/controller/controller_changan_shenlan/main.cpp

@@ -143,7 +143,7 @@ void executeDecition(const iv::brain::decition decition)
 //    _m24B->ACC_Driveoff_Request = 0;
 //    _m24B->ACC_DecToStop = 0;
     _m24B->ACC_CDDActive = decition.brake_active();
-    _m24B->ACC_ACCMode = 3;
+    _m24B->ACC_ACCMode = decition.auto_mode();
 
     byte_24B[0] |= ((_m24B->ACC_AccTrqReq >> 7) & (0xFFU));
     byte_24B[1] |= ((_m24B->ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B->ACC_AccTrqReqActive & (0x01U));
@@ -163,73 +163,6 @@ void executeDecition(const iv::brain::decition decition)
 
     byte_36E[0] |= ((_m36E->ADS_UDLCTurnLightReq & (0x07U)) << 5);
 
-
-#if 0
-    //    std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
-
-    gcontroller->control_acc_en(true);
-    gcontroller->control_angle_enable(true);
-    gcontroller->control_gear_en(true);
-    gcontroller->control_speed_limit(30);
-
-    gcontroller->control_wheel(decition.wheelangle());
-    gcontroller->control_angle_speed(decition.wheelspeed());
-    gcontroller->control_torque(decition.torque());
-
-    gcontroller->control_brake(decition.brake());
-    gcontroller->control_gear(decition.gear());
-
-    gcontroller->control_handBrake(decition.handbrake());
-    gcontroller->control_mode(decition.mode());
-    //   gcontroller->control_mode(1);
-    gcontroller->control_near_light(decition.dippedlight());
-
-
-    //gcontroller->control_air_enable(decition.air_enable());
-    //gcontroller->control_air_on(decition.air_on());
-    //gcontroller->control_air_temp(decition.air_temp());
-    //gcontroller->control_air_mode(decition.air_mode());
-    //gcontroller->control_wind_level(decition.wind_level());
-    gcontroller->control_roof_light(decition.roof_light());
-    gcontroller->control_home_light(decition.home_light());
-    //gcontroller->control_air_worktime(decition.air_worktime());
-    //gcontroller->control_air_offtime(decition.air_offtime());
-    gcontroller->control_turnsignals(decition.leftlamp(),decition.rightlamp());
-    gcontroller->control_door(decition.door());
-
-#ifdef TORQUEBRAKETEST
-    if(gnothavetb < 10)
-    {
-        iv::controller::torquebrake xtb;
-        gMutextb.lock();
-        xtb.CopyFrom(gtb);
-        gMutextb.unlock();
-        if(xtb.enable())
-        {
-            gcontroller->control_torque(xtb.torque());
-            gcontroller->control_brake(xtb.brake());
-            qDebug("use tb value torque is %f brake is %f",xtb.torque(),xtb.brake());
-        }
-        else
-        {
-            //            qDebug("torquebrake not enable.");
-        }
-        gnothavetb++;
-    }
-
-#endif
-
-
-
-
-    //qDebug("door is %d",decition.door());
-
-    gcontroller->cmd_checksum(0x10);
-    gcontroller->cmd_checksum(0x11);
-    gcontroller->cmd_checksum(0x12);
-
-    //    qDebug("dangwei is %d mode is %d",decition.gear(),decition.mode());
-#endif
 }
 
 void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
@@ -249,8 +182,6 @@ void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned
     {
         gbChassisEPS = true;
     }
-
-
 }
 
 
@@ -268,10 +199,10 @@ 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");
+//    }
     if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
     oldtime = QDateTime::currentMSecsSinceEpoch();
     gMutex.lock();
@@ -287,8 +218,7 @@ void ExecSend()
     iv::can::canmsg xmsg;
     iv::can::canraw xraw;
     //    unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
-    //    qDebug("%02x %02x %02x %02x %02x %02x %02x %02x",strp[0]
-    //            ,strp[1],strp[2],strp[3],strp[4],strp[5],strp[6],strp[7]);
+    //    qDebug("%02x %02x %02x %02x %02x %02x %02x %02x",strp[0],strp[1],strp[2],strp[3],strp[4],strp[5],strp[6],strp[7]);
 
     xraw.set_id(0x144);
     xraw.set_data(byte_144,8);
@@ -320,43 +250,6 @@ void ExecSend()
     xmsg.set_channel(0);
     xmsg.set_index(gnIndex);
 
-
-
-    //    xraw.set_id(ServiceControlStatus.command_ID10);
-    //    xraw.set_data(ServiceControlStatus.command10.byte,8);
-    //    xraw.set_bext(false);
-    //    xraw.set_bremote(false);
-    //    xraw.set_len(8);
-    //    iv::can::canraw * pxraw = xmsg.add_rawmsg();
-    //    pxraw->CopyFrom(xraw);
-    //    xmsg.set_channel(0);
-    //    xmsg.set_index(gnIndex);
-
-    //    xraw.set_id(ServiceControlStatus.command_ID11);
-    //    xraw.set_data(ServiceControlStatus.command11.byte,8);
-    //    int a = ServiceControlStatus.command11.byte[5]&0x0f;
-    //    if(a != 0x04)
-    //    {
-    //        qDebug("not D.");
-    //    }
-    //    xraw.set_bext(false);
-    //    xraw.set_bremote(false);
-    //    xraw.set_len(8);
-    //    iv::can::canraw * pxraw1 = xmsg.add_rawmsg();
-    //    pxraw1->CopyFrom(xraw);
-    //    xmsg.set_channel(0);
-    //    xmsg.set_index(gnIndex);
-
-    //    xraw.set_id(ServiceControlStatus.command_ID12);
-    //    xraw.set_data(ServiceControlStatus.command12.byte,8);
-    //    xraw.set_bext(false);
-    //    xraw.set_bremote(false);
-    //    xraw.set_len(8);
-    //    iv::can::canraw * pxraw2 = xmsg.add_rawmsg();
-    //    pxraw2->CopyFrom(xraw);
-    //    xmsg.set_channel(0);
-    //    xmsg.set_index(gnIndex);
-
     gnIndex++;
     xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
     int ndatasize = xmsg.ByteSize();
@@ -375,14 +268,6 @@ void ExecSend()
 
 void initial()
 {
-    //    ServiceControlStatus.command.byte[0] = 0;
-    //    ServiceControlStatus.command.byte[1] = 0;
-    //    ServiceControlStatus.command.byte[2] = 0;
-    //    ServiceControlStatus.command.byte[3] = 0;
-    //    ServiceControlStatus.command.byte[4] = 0;
-    //    ServiceControlStatus.command.byte[5] = 0;
-    //    ServiceControlStatus.command.byte[6] = 0;
-    //    ServiceControlStatus.command.byte[7] = 0;
     for (uint8_t i = 0; i < 8; i++)
     {
         byte_144[i] = 0;
@@ -430,16 +315,15 @@ int main(int argc, char *argv[])
     std::cout<<strpath.toStdString()<<std::endl;
 
     gdecition_def.set_accelerator(-0.5);
-//    gdecition_def.set_brake(20);
-//    gdecition_def.set_torque(0);
-     gdecition_def.set_rightlamp(true);
-    //  gdecition_def.set_doublespark(true);
+    gdecition_def.set_rightlamp(true);
     gdecition_def.set_wheelangle(0);
-//    gdecition_def.set_mode(1);
-//    gdecition_def.set_grade(1);
-//    gdecition_def.set_gear(1);
-//    gdecition_def.set_engine(0);
-    //    gdecition_def.set_gear(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);
+
     gTime.start();
 
     gcontroller = boost::shared_ptr<iv::control::Controller>(new iv::control::Controller());

+ 23 - 17
src/decition/decition_brain_sf_changan_shenlan/decition/adc_adapter/changan_shenlan_adapter.cpp

@@ -20,7 +20,7 @@ iv::decition::ChanganShenlanAdapter::~ChanganShenlanAdapter(){
 
 
 iv::decition::Decition iv::decition::ChanganShenlanAdapter::getAdapterDeciton(GPS_INS now_gps_ins, std::vector<Point2D>  trace , float dSpeed, float obsDistance ,
-                                                                   float  obsSpeed,float accAim,float accNow  ,bool changingDangWei,Decition *decition){
+                                                                              float  obsSpeed,float accAim,float accNow  ,bool changingDangWei,Decition *decition){
 
 
     float controlSpeed=0;
@@ -85,11 +85,11 @@ iv::decition::Decition iv::decition::ChanganShenlanAdapter::getAdapterDeciton(GP
     controlBrake=min(controlBrake,100.0f);
     controlBrake=max(controlBrake,0.0f);
 
-//    (*decition)->brake = controlBrake;
+    //    (*decition)->brake = controlBrake;
 
-//    (*decition)->torque= controlSpeed;
+    //    (*decition)->torque= controlSpeed;
 
-//    lastTorque=(*decition)->torque;
+    //    lastTorque=(*decition)->torque;
     (*decition)->accelerator = 0 - controlBrake/25;
     (*decition)->niuju_y = controlSpeed;
     lastTorque = (*decition)->niuju_y;
@@ -106,19 +106,25 @@ iv::decition::Decition iv::decition::ChanganShenlanAdapter::getAdapterDeciton(GP
         (*decition)->acc_active = 1;
     }
 
-//    (*decition)->grade=1;
-//    (*decition)->mode=1;
-//    (*decition)->speak=0;
-//    (*decition)->handBrake=0;
-//    (*decition)->bright=false;
-//    (*decition)->engine=0;
-
-//    if(ServiceCarStatus.bocheMode){
-//        (*decition)->dangWei=2;
-//    }else{
-//        (*decition)->dangWei=1;
-//    }
-
+    //    (*decition)->grade=1;
+    //    (*decition)->mode=1;
+    //    (*decition)->speak=0;
+    //    (*decition)->handBrake=0;
+    //    (*decition)->bright=false;
+    //    (*decition)->engine=0;
+
+    //    if(ServiceCarStatus.bocheMode){
+    //        (*decition)->dangWei=2;
+    //    }else{
+    //        (*decition)->dangWei=1;
+    //    }
+
+    (*decition)->acc_active = 1;//ACC扭矩请求激活(为1激活,为0不激活),不激活后不执行扭矩请求
+    (*decition)->brake_active = 1;//ACC减速激活(为1制动激活,为0制动不激活)
+    (*decition)->brake_type = 1;//ADC请求类型(制动时为1,其余情况为0)
+    (*decition)->angle_active = 1;//横向控制激活模式
+    (*decition)->angle_mode = 2; //横向控制激活,和上一条同时满足才执行横向请求角度
+    (*decition)->auto_mode = 3; //3为自动控制模式
 
     (*decition)->wheel_angle=max((float)-500.0,float((*decition)->wheel_angle+ServiceCarStatus.mfEPSOff));
     (*decition)->wheel_angle=min((float)500.0,(*decition)->wheel_angle);

+ 4 - 1
src/decition/decition_brain_sf_changan_shenlan/decition/decition_type.h

@@ -51,10 +51,13 @@ struct DecitionBasic {
     float   air_worktime ;                  //空调工作时间
     float   air_offtime ;                  //空调关闭时间
 
-    float niuju_y;
+    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为自动控制模式
 
 };
 typedef boost::shared_ptr<DecitionBasic> Decition;	//决策

+ 7 - 4
src/include/proto/decition.proto

@@ -50,8 +50,11 @@ message decition
 	optional uint32 window_rl = 43;
 	optional uint32 window_rr = 44;
     //chang_an_shen_lan
-	optional uint32 acc_active = 45; //ACC扭矩请求激活(为1激活,为0不激活),不激活后不执行扭矩请求
-	optional uint32 brake_active = 46; //ACC减速激活(为1制动激活,为0制动不激活)
-	optional uint32 brake_type = 47;//ADC请求类型(制动时为1,其余情况为0)
-	optional float niuju_y = 48; //纵向扭矩
+	optional uint32 angle_mode = 45;  //横向控制激活模式
+	optional uint32 angle_active = 46; //横向控制激活,和上一条同时满足才执行横向请求角度 
+	optional uint32 acc_active = 47; //ACC扭矩请求激活(为1激活,为0不激活),不激活后不执行扭矩请求
+	optional uint32 brake_active = 48; //ACC减速激活(为1制动激活,为0制动不激活)
+	optional uint32 brake_type = 49;//ADC请求类型(制动时为1,其余情况为0)
+	optional float niuju_y = 50; //纵向扭矩
+	optional uint32 auto_mode = 51; //3为自动控制模式
 };