|
@@ -114,27 +114,33 @@ ECU_144_t _m144 = {0,0,0,0,0,0};
|
|
|
ECU_24B_t _m24B = {0,0,0,0,0,0,0,0,0,0,0};
|
|
|
ECU_36E_t _m36E = {0};
|
|
|
|
|
|
+void ExecSend();
|
|
|
|
|
|
void executeDecition(const iv::brain::decition &decition)
|
|
|
{
|
|
|
- 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;
|
|
|
+// 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);
|
|
|
_m144.ACC_LatAngReqActive = decition.angle_active();
|
|
|
_m144.ACC_MotorTorqueMinLimitRequest = ECU_144_ACC_MotorTorqueMinLimitRequest_toS(-10);
|
|
|
- _m144.ACC_ADCReqType = decition.brake_type();//ADC请求类型(制动时为1,其余情况为0)
|
|
|
+// _m144.ACC_ADCReqType = decition.brake_type();//ADC请求类型(制动时为1,其余情况为0)
|
|
|
+ _m144.ACC_ADCReqType = 0;//ADC请求类型(制动时为1,其余情况为0)
|
|
|
|
|
|
- byte_144[0] |= ((_m144.ACC_LatAngReq >> 9) & (0x1FU)) | ((_m144.ADS_Reqmode & (0x07U)) << 5);
|
|
|
- byte_144[1] |= ((_m144.ACC_LatAngReq >> 1) & (0xFFU));
|
|
|
- byte_144[2] |= ((_m144.ACC_LatAngReq & (0x01U)) << 7) | ((_m144.ACC_MotorTorqueMaxLimitRequest >> 5) & (0x3FU)) | ((_m144.ACC_LatAngReqActive & (0x01U)) << 6);
|
|
|
- byte_144[3] |= ((_m144.ACC_MotorTorqueMaxLimitRequest & (0x1FU)) << 3) | ((_m144.ACC_MotorTorqueMinLimitRequest >> 8) & (0x07U));
|
|
|
- byte_144[4] |= (_m144.ACC_MotorTorqueMinLimitRequest & (0xFFU));
|
|
|
- byte_144[5] |= ((_m144.ACC_ADCReqType & (0x03U)) << 6);
|
|
|
+
|
|
|
+
|
|
|
+// std::cout<<" req mode: "<<_m144.ADS_Reqmode<<std::endl;
|
|
|
+ byte_144[0] = ((_m144.ACC_LatAngReq >> 9) & (0x1FU)) | ((_m144.ADS_Reqmode & (0x07U)) << 5);
|
|
|
+ qDebug(" req mode: %d byte: %02X ",_m144.ADS_Reqmode, byte_144[0]);
|
|
|
+ byte_144[1] = ((_m144.ACC_LatAngReq >> 1) & (0xFFU));
|
|
|
+ byte_144[2] = ((_m144.ACC_LatAngReq & (0x01U)) << 7) | ((_m144.ACC_MotorTorqueMaxLimitRequest >> 5) & (0x3FU)) | ((_m144.ACC_LatAngReqActive & (0x01U)) << 6);
|
|
|
+ byte_144[3] = ((_m144.ACC_MotorTorqueMaxLimitRequest & (0x1FU)) << 3) | ((_m144.ACC_MotorTorqueMinLimitRequest >> 8) & (0x07U));
|
|
|
+ byte_144[4] = (_m144.ACC_MotorTorqueMinLimitRequest & (0xFFU));
|
|
|
+ byte_144[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
|
|
|
|
|
|
/*制动过程用的减速度,加速用扭矩*/
|
|
|
_m24B.ACC_AccTrqReq = ECU_24B_ACC_AccTrqReq_toS(decition.torque());
|
|
@@ -149,14 +155,14 @@ void executeDecition(const iv::brain::decition &decition)
|
|
|
_m24B.ACC_CDDActive = decition.brake_active();
|
|
|
_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));
|
|
|
- byte_24B[2] |= ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
|
|
|
- byte_24B[3] |= ((_m24B.ACC_ACCTargetAcceleration & (0x07U)) << 5) | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
|
|
|
- byte_24B[4] |= ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
|
|
|
- byte_24B[5] |= ((_m24B.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24B.ACC_AEBVehilceHoldReq & (0x01U));
|
|
|
- byte_24B[6] |= ((_m24B.ADCReqMode & (0x03U)) << 1) | ((_m24B.ACC_AEBActive & (0x01U)) << 3) | ((_m24B.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24B.ACC_DecToStop & (0x01U)) << 6) | ((_m24B.ACC_CDDActive & (0x01U)) << 7);
|
|
|
- byte_24B[7] |= (_m24B.ACC_ACCMode & (0x07U));
|
|
|
+ byte_24B[0] = ((_m24B.ACC_AccTrqReq >> 7) & (0xFFU));
|
|
|
+ byte_24B[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
|
|
|
+ byte_24B[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
|
|
|
+ byte_24B[3] = ((_m24B.ACC_ACCTargetAcceleration & (0x07U)) << 5) | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
|
|
|
+ byte_24B[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
|
|
|
+ byte_24B[5] = ((_m24B.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24B.ACC_AEBVehilceHoldReq & (0x01U));
|
|
|
+ byte_24B[6] = ((_m24B.ADCReqMode & (0x03U)) << 1) | ((_m24B.ACC_AEBActive & (0x01U)) << 3) | ((_m24B.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24B.ACC_DecToStop & (0x01U)) << 6) | ((_m24B.ACC_CDDActive & (0x01U)) << 7);
|
|
|
+ byte_24B[7] = (_m24B.ACC_ACCMode & (0x07U));
|
|
|
|
|
|
if(decition.leftlamp() == true && decition.rightlamp() == false)
|
|
|
_m36E.ADS_UDLCTurnLightReq = 3;
|
|
@@ -165,10 +171,73 @@ void executeDecition(const iv::brain::decition &decition)
|
|
|
else
|
|
|
_m36E.ADS_UDLCTurnLightReq = 0;
|
|
|
|
|
|
- byte_36E[0] |= ((_m36E.ADS_UDLCTurnLightReq & (0x07U)) << 5);
|
|
|
+ byte_36E[0] = ((_m36E.ADS_UDLCTurnLightReq & (0x07U)) << 5);
|
|
|
|
|
|
}
|
|
|
|
|
|
+void Activate()
|
|
|
+{
|
|
|
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
|
|
+ iv::brain::decition xdecition;
|
|
|
+// for(int j=0;j<100000;j++)
|
|
|
+// {
|
|
|
+ std::cout<<" run "<<std::endl;
|
|
|
+ for(int i = 0; i < 10; i++){
|
|
|
+ xdecition.set_wheelangle(0.0);
|
|
|
+ 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 < 10; i++){
|
|
|
+ xdecition.set_wheelangle(0.0);
|
|
|
+ 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));
|
|
|
+ }
|
|
|
+// }
|
|
|
+}
|
|
|
+
|
|
|
+void UnAcitvate()
|
|
|
+{
|
|
|
+ iv::brain::decition xdecition;
|
|
|
+ for(int i = 0; i < 10; i++){
|
|
|
+ xdecition.set_wheelangle(0);
|
|
|
+ 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));
|
|
|
+ }
|
|
|
+ for(int i = 0; i < 10; i++){
|
|
|
+ xdecition.set_wheelangle(0);
|
|
|
+ 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));
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
|
|
|
{
|
|
|
(void)index;
|
|
@@ -211,7 +280,7 @@ void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned
|
|
|
xdecition.set_angle_active(1);
|
|
|
xdecition.set_acc_active(1);
|
|
|
xdecition.set_brake_active(1);
|
|
|
- xdecition.set_brake_type(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());
|
|
@@ -240,6 +309,8 @@ void ExecSend()
|
|
|
xraw.set_len(8);
|
|
|
iv::can::canraw * pxraw144 = xmsg.add_rawmsg();
|
|
|
pxraw144->CopyFrom(xraw);
|
|
|
+ qDebug(" 0x144: %02X %02X %02X %02X %02X %02X %02X %02X",byte_144[0],byte_144[1],byte_144[2],byte_144[3],
|
|
|
+ byte_144[4],byte_144[5],byte_144[6],byte_144[7]);
|
|
|
xmsg.set_channel(0);
|
|
|
xmsg.set_index(gnIndex);
|
|
|
|
|
@@ -294,7 +365,6 @@ void initial()
|
|
|
byte_24B[i] = 0;
|
|
|
byte_36E[i] = 0;
|
|
|
}
|
|
|
-
|
|
|
}
|
|
|
|
|
|
void sendthread()
|
|
@@ -302,38 +372,29 @@ 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));
|
|
|
- }
|
|
|
-
|
|
|
+ UnAcitvate();
|
|
|
+ // UnAcitvate();
|
|
|
|
|
|
+ int nstate = 0; //0 Un 1 Activate
|
|
|
+// Activate();
|
|
|
while(gbSendRun)
|
|
|
{
|
|
|
if(gnDecitionNum <= 0)
|
|
|
{
|
|
|
+ if(nstate == 1)
|
|
|
+ {
|
|
|
+ UnAcitvate();
|
|
|
+ nstate = 0;
|
|
|
+ }
|
|
|
xdecition.CopyFrom(gdecition_def);
|
|
|
}
|
|
|
else
|
|
|
{
|
|
|
+ if(nstate == 0)
|
|
|
+ {
|
|
|
+ Activate();
|
|
|
+ nstate = 1;
|
|
|
+ }
|
|
|
gMutex.lock();
|
|
|
xdecition.CopyFrom(gdecition);
|
|
|
gMutex.unlock();
|
|
@@ -360,15 +421,24 @@ int main(int argc, char *argv[])
|
|
|
std::cout<<strpath.toStdString()<<std::endl;
|
|
|
|
|
|
// gdecition_def.set_accelerator(-0.5);
|
|
|
- gdecition_def.set_brake(-0.5);
|
|
|
- gdecition_def.set_rightlamp(true);
|
|
|
+ gdecition_def.set_brake(0);
|
|
|
+ gdecition_def.set_rightlamp(false);
|
|
|
+ gdecition_def.set_leftlamp(false);
|
|
|
gdecition_def.set_wheelangle(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);
|
|
|
+
|
|
|
+ gdecition_def.set_angle_mode(0);
|
|
|
+ gdecition_def.set_angle_active(0);
|
|
|
+ gdecition_def.set_acc_active(0);
|
|
|
+// gdecition_def.set_brake_active(1);
|
|
|
+ gdecition_def.set_brake_type(0);
|
|
|
+ gdecition_def.set_auto_mode(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();
|
|
|
|