|
@@ -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());
|