소스 검색

controller and decition

lijinliang 3 년 전
부모
커밋
8cbbb68a6b

+ 22 - 14
src/controller/controller_Geely_xingyueL/include/basic_types.h

@@ -1,8 +1,10 @@
 #ifndef CAR_CONTROL_H
 #define CAR_CONTROL_H
 
-#include "include/kx_11_can_frame/chassis_can1_frame.h"
-#include "include/kx_11_can_frame/asdm_sim_canfd_frame.h"
+#include "kx_11_can_frame/chassis_can1_frame.h"
+#include "kx_11_can_frame/asdm_sim_canfd_frame.h"
+#include <thread>
+
 
 enum class StsMach
 {
@@ -36,7 +38,6 @@ public:
   CarControl();
   ~CarControl();
 
-  void sm_task_20ms();
 
   void set_lat_lgt_ctrl_req(bool req);
   void set_target_gear(GearPrkgAssistReq tar);
@@ -44,6 +45,8 @@ public:
   void set_target_pinion_ag_in_deg(float32_t ang_req);
   void set_target_acc_mps2(float32_t tar_acc);
   void set_turn_light_status(TurnLightIndicReq req);
+  void set_ctrl_mode_switch_spd(float32_t spd_kmh);
+  void set_debug_log_para(bool enable, uint16_t print_cycle_ms);
   ChassisErrCode get_chassis_err_state();
   StsMach get_chassis_statemachine_sts();
   float32_t get_current_steer_ang_in_deg();
@@ -51,6 +54,8 @@ public:
   GearPrkgAssistReq get_setted_tar_gear();
   GearLevelIndicate get_cur_disp_gear();
 private:
+  void sm_task_20ms();
+  void sm_task_thread();
   bool is_chassis_system_failure();
   bool is_hwa_switched();
   void apa_active_ctrl();
@@ -62,35 +67,38 @@ private:
   void apa_startup_action();
   void hwa_pre_active();
 private:
-  ChassisCAN1_Process *chassis_obj_ptr_;
-  ASDM_Sim_Process *asdm_obj_ptr_;
-  StsMach sm_ = StsMach::kStandby;
-  bool is_chassis_handshake_timeout;
+  ChassisCAN1_Process *chassis_obj_ptr_{nullptr};
+  ASDM_Sim_Process *asdm_obj_ptr_{nullptr};
+  StsMach sm_{StsMach::kStandby};
+  std::unique_ptr<std::thread> thread_sm_task_{nullptr};
+  bool is_chassis_handshake_timeout{false};
 
-  bool is_lat_lgt_ctrl_requested_;
-  GearPrkgAssistReq tar_gear_;
-  float32_t tar_pinion_ang_in_deg_;
-  float32_t tar_acc_meter_per_second2_;
+  bool is_lat_lgt_ctrl_requested_{false};
+  GearPrkgAssistReq tar_gear_{GearPrkgAssistReq::kNoRequest};
+  float32_t tar_pinion_ang_in_deg_{0};
+  float32_t tar_acc_meter_per_second2_{0};
 
   uint16_t time_startup_ = 0;
   uint16_t timeout_apa_startup = 0;
   uint16_t timeout_apa_shutdown = 0;
   uint16_t timeout_hwa_startup = 0;
   uint16_t timeout_hwa_shutdown = 0;
-  uint16_t time_handshake_timeout_disappear = 0;
   const uint16_t kMaxStartupDlyTime = (3000 / 20); // uinit:ms
   const uint16_t kMaxApaStartupTime = (3000 / 20); // uinit:ms
   const uint16_t kMaxApaShutdownTime = (10000 / 20); // uinit:ms
   const uint16_t kMaxHwaStartupTime = (5000 / 20); // uinit:ms
   const uint16_t kMaxHwaShutdownTime = (10000 / 20); // uinit:ms
-  const uint16_t kMaxHandshakeTimeoutDispTime = (4000 / 20); // uinit:ms
-  const float32_t kSpeedForCtrlModSwitch = CONVERT_KPH_2_MPS(6);   // the APA longitude speed uppper limit is 10km/h
+  float32_t kSpeedForCtrlModSwitch = CONVERT_KPH_2_MPS(6);   // the APA longitude speed uppper limit is 10km/h
   const float32_t kSteerDiffMax = 90;
   const float32_t kSteerDiffMin = -90;
   const float32_t kSteerMaxAng = 450;
   const float32_t kSteerMinAng = -450;
   const float32_t kApaShutDownDecel = -1.28; //uinit: m/s^2, apa max deceleration.
   const float32_t kHwaShutDownDecel = -5; //uinit: m/s^2, hwa shutdown deceleration value.
+
+  // debug parameter:
+  bool debug_enable_{false};
+  uint16_t print_period_ms_{20};
 };
 
 #endif

+ 40 - 49
src/controller/controller_Geely_xingyueL/include/kx_11_can_frame/asdm_sim_canfd_data_type.h

@@ -91,14 +91,6 @@ enum class PrkgEngRunngReq
   kReserved = 3
 };
 
-enum class PrkgEcuType
-{
-  kPAS1 = 0,
-  kPAS2 = 1,
-  kPAS3 = 2
-};
-
-
 // PAS Frame18
 enum class PrkgFctVmmDriveModReq
 {
@@ -283,51 +275,50 @@ enum class TurnLightIndicReq
 struct AsdmControlRequest
 {
   /* data */
-  PrkgStandStillReq standstill_req;
-  PrkgBrakeFctMode brake_mode;
-  float32_t acc_lower_limit; // m/s^2
-  float32_t acc_lower_slope; // m/s^3
-  float32_t acc_request;  // m/s^2
-  float32_t acc_upper_limit; // m/s^2
-  float32_t acc_upper_slope; // m/s^3
-  PrkgEpbReq epb_ctrl_req;
-  PrkgCtrlModReq contrl_mod_req;
-  RpaAuthentReq authent_req_sts;
-  uint32_t authent_req_rndx;
-  uint32_t authent_req_rndy;
-  GearPrkgAssistReq target_gear;
-  PrkgEngRunngReq engine_keep_run_req;
-  PrkgEcuType prkg_ecu_type;
-  DriveAssistSysSts prkg_drive_assist_sys_sts;
-  AsyLatCtrlModReq latitude_ctrl_req;
-  AsyALgtCtrlModReq longitude_ctrl_req;
-  AccStatus acc_func_ctrl_status;
-
-  bool acc_func_standstill_req;
-  bool acc_func_driveoff_req;
-  float32_t acc_func_neg_limit_jerk;  // unit: m/s^3
-  float32_t acc_func_pos_limit_jerk;  // unit: m/s^3
-  float32_t acc_func_taracc_cmft_max;  // unit: m/s^2
-  float32_t acc_func_taracc_cmft_min;  // unit: m/s^2
-  TurnLightIndicReq turn_light_req;
+  PrkgStandStillReq standstill_req{PrkgStandStillReq::kNotRequested};
+  PrkgBrakeFctMode brake_mode{PrkgBrakeFctMode::kDefault};
+  float32_t acc_lower_limit{0}; // m/s^2
+  float32_t acc_lower_slope{0}; // m/s^3
+  float32_t acc_request{0};  // m/s^2
+  float32_t acc_upper_limit{0}; // m/s^2
+  float32_t acc_upper_slope{0}; // m/s^3
+  PrkgEpbReq epb_ctrl_req{PrkgEpbReq::kNoRequest};
+  PrkgCtrlModReq contrl_mod_req{PrkgCtrlModReq::kNoRequest};
+  RpaAuthentReq authent_req_sts{RpaAuthentReq::kNone};
+  uint32_t authent_req_rndx{0};
+  uint32_t authent_req_rndy{0};
+  GearPrkgAssistReq target_gear{GearPrkgAssistReq::kNoRequest};
+  PrkgEngRunngReq engine_keep_run_req{PrkgEngRunngReq::kDefault};
+  DriveAssistSysSts prkg_drive_assist_sys_sts{DriveAssistSysSts::kOff};
+  AsyLatCtrlModReq latitude_ctrl_req{AsyLatCtrlModReq::kNoReq};
+  AsyALgtCtrlModReq longitude_ctrl_req{AsyALgtCtrlModReq::kNoReq};
+  AccStatus acc_func_ctrl_status{AccStatus::kStandby};
+
+  bool acc_func_standstill_req{false};
+  bool acc_func_driveoff_req{false};
+  float32_t acc_func_neg_limit_jerk{0};  // unit: m/s^3
+  float32_t acc_func_pos_limit_jerk{0};  // unit: m/s^3
+  float32_t acc_func_taracc_cmft_max{0};  // unit: m/s^2
+  float32_t acc_func_taracc_cmft_min{0};  // unit: m/s^2
+  TurnLightIndicReq turn_light_req{TurnLightIndicReq::kOff};
 };
 
 struct VddmFeedback
 {
-  float32_t vehicle_spd_lgt;  // uinit: m/s
-  float32_t vehicle_internal_acc;  // unit: m/s^2
-  VehicleMoveStatus vehicle_movement_sts;
-  StandstillStsForHld standstill_hold_sts;
-  PrkgLatLgtFailr prkg_lat_lgt_failure;
-  EngineWorkStatus engine_work_status;
-  float32_t acceleration_pedal_rate; // 0% ~ 100%
-  CarModeSts car_mode;
-  UsageModeSts usage_mode;
-  GearLevelIndicate current_gear;
-  EpbStatus epb_status;
-  BrakePedalPosition brake_pedal_posn;
-  CfmdLatCtrlMod lat_ctrl_mod_feedback;
-  CfmdLgtCtrlMod lgt_ctrl_mod_feedback;
+  float32_t vehicle_spd_lgt{0};  // uinit: m/s
+  float32_t vehicle_internal_acc{0};  // unit: m/s^2
+  VehicleMoveStatus vehicle_movement_sts{VehicleMoveStatus::kUnknown};
+  StandstillStsForHld standstill_hold_sts{StandstillStsForHld::kHldVal0};
+  PrkgLatLgtFailr prkg_lat_lgt_failure{PrkgLatLgtFailr::kNoFailure};
+  EngineWorkStatus engine_work_status{EngineWorkStatus::kInit};
+  float32_t acceleration_pedal_rate{0}; // 0% ~ 100%
+  CarModeSts car_mode{CarModeSts::kNorm};
+  UsageModeSts usage_mode{UsageModeSts::kInactive};
+  GearLevelIndicate current_gear{GearLevelIndicate::kUndefined};
+  EpbStatus epb_status{EpbStatus::kAllApplied};
+  BrakePedalPosition brake_pedal_posn{BrakePedalPosition::kNoPressed};
+  CfmdLatCtrlMod lat_ctrl_mod_feedback{CfmdLatCtrlMod::kNoReq};
+  CfmdLgtCtrlMod lgt_ctrl_mod_feedback{CfmdLgtCtrlMod::kNoReq};
 };
 
 #endif

+ 1 - 1
src/controller/controller_Geely_xingyueL/include/kx_11_can_frame/asdm_sim_canfd_frame.h

@@ -1,7 +1,7 @@
 #ifndef ASDM_CANFD4_FRAME_H
 #define ASDM_CANFD4_FRAME_H
 
-#include "include/socket_can_interface/socket_can_interface.h"
+#include "./include/socket_can_interface/socket_can_interface.h"
 #include "can_canfd_common.h"
 #include "asdm_sim_canfd_data_type.h"
 

+ 9 - 43
src/controller/controller_Geely_xingyueL/include/kx_11_can_frame/can_canfd_common.h

@@ -2,7 +2,7 @@
 #define CAN_CANFD_COMMON_H
 
 #include <pthread.h>
-#include "include/socket_can_interface/socket_can_interface.h"
+#include "./include/socket_can_interface/socket_can_interface.h"
 
 
 #define DOMAIN_ECU_PASSWORD "nvidia"
@@ -20,63 +20,29 @@
 typedef struct
 {
   /* data */
-  can_frame fr;       // can frame 
-  bool is_updated;       // if receive a new frame , it's updated , so need be processed
-  bool need_passthrough; // need pass this can raw data to next can bus
-} ReceiveAndPassthroughFrame;
-
-typedef struct
-{
-  /* data */
-  can_frame fr;       // can raw data
-  can_frame mdf_fr;   // modify the vehicle status.
-  bool is_updated;       // if receive a new frame , it's updated , so need be processed
-  bool need_passthrough; // need pass this can raw data to next can bus
-} ReceiveAndPassthroughModifyFrame;
-
-typedef struct
-{
-  /* data */
-  canfd_frame fr;       // canfd frame 
-  bool is_updated;       // if receive a new frame , it's updated , so need be processed
-  bool need_passthrough; // need pass this can raw data to next can bus
-} ReceiveAndPassthroughFrameCanfd;
-
-typedef struct
-{
-  /* data */
-  canfd_frame fr;       // can fd raw data
-  canfd_frame mdf_fr;   // modify the vehicle status.
-  bool is_updated;       // if receive a new frame , it's updated , so need be processed
-  bool need_passthrough; // need pass this can raw data to next can bus
-} ReceiveAndPassthroughModifyFrameCanfd;
-
-typedef struct
-{
-  /* data */
-  can_frame fr;       // can frame 
-  bool is_updated; // if receive a new frame , it's updated , so need be processed
+  can_frame fr{0, 0, 0, 0, 0, {0}};       // can frame 
+  bool is_updated{false}; // if receive a new frame , it's updated , so need be processed
 } ReceiveFrame;
 
 typedef struct
 {
   /* data */
-  can_frame fr;       // can frame 
-  bool need_send;  // if need send can frame to can bus ,set this to true
+  can_frame fr{0, 0, 0, 0, 0, {0}};       // can frame 
+  bool need_send{false};  // if need send can frame to can bus ,set this to true
 } SendFrame;
 
 typedef struct
 {
   /* data */
-  canfd_frame fr;       // can fd frame 
-  bool is_updated; // if receive a new frame , it's updated , so need be processed
+  canfd_frame fr{0, 0, 0, 0, 0, {0}};       // can fd frame 
+  bool is_updated{false}; // if receive a new frame , it's updated , so need be processed
 } ReceiveFrameCanfd;
 
 typedef struct
 {
   /* data */
-  canfd_frame fr;       // can fd frame 
-  bool need_send;  // if need send can frame to can bus ,set this to true
+  canfd_frame fr{0, 0, 0, 0, 0, {0}};       // can fd frame 
+  bool need_send{false};  // if need send can frame to can bus ,set this to true
 } SendFrameCanfd;
 
 enum class GenQf1

+ 17 - 17
src/controller/controller_Geely_xingyueL/include/kx_11_can_frame/chassis_can1_frame.h

@@ -1,7 +1,7 @@
 #ifndef CHASSIS_CAN1_FRAME_H
 #define CHASSIS_CAN1_FRAME_H
 
-#include "include/socket_can_interface/socket_can_interface.h"
+#include "./include/socket_can_interface/socket_can_interface.h"
 #include "can_canfd_common.h"
 
 
@@ -29,9 +29,9 @@ enum class DrvrWheelHoldSts
 
 struct AccFuncPinionCtrReq
 {
-  float32_t torque_upper_limit;
-  float32_t torque_lower_limit;
-  float32_t pinion_ang_req_in_deg;
+  float32_t torque_upper_limit{0};
+  float32_t torque_lower_limit{0};
+  float32_t pinion_ang_req_in_deg{0};
 };
 
 
@@ -44,22 +44,22 @@ public:
   void set_filters();
 public:
   // output parameters
-  SteerStsToParkAssis steer_sts;
-  DrvrWheelHoldSts driver_wheel_hold_sts;
-  bool dirver_steering_is_active;
-  bool is_steer_servious_sts;
-  float32_t cur_pinion_steer_ag1_in_deg;
+  SteerStsToParkAssis steer_sts{SteerStsToParkAssis::kNormOper};
+  DrvrWheelHoldSts driver_wheel_hold_sts{DrvrWheelHoldSts::kNoInfo};
+  bool driver_steering_is_active{false};
+  bool is_steer_servious_sts{false};
+  float32_t cur_pinion_steer_ag1_in_deg{0};
   
-  bool pinion_steer_ag1_valid;
-  float32_t pinion_steerAgSpd1_deg_in_per_sec;
-  bool pinion_steer_ag_spd1_valid;
-  float32_t steer_wheel_torque;
-  bool steer_wheel_torque_valid;
-  bool vfc_info_enable;
+  bool pinion_steer_ag1_valid{false};
+  float32_t pinion_steerAgSpd1_deg_in_per_sec{0};
+  bool pinion_steer_ag_spd1_valid{false};
+  float32_t steer_wheel_torque{0};
+  bool steer_wheel_torque_valid{false};
+  bool vfc_info_enable{false};
 
   // input parameters
-  float32_t pas_pinion_ang_req_in_deg;
-  bool is_pas_func_active;
+  float32_t pas_pinion_ang_req_in_deg{0};
+  bool is_pas_func_active{false};
   struct AccFuncPinionCtrReq acc_func_pinion_ctrl_req;
 
 private:

+ 2 - 2
src/controller/controller_Geely_xingyueL/include/socket_can_interface/socket_can_interface.h

@@ -16,8 +16,8 @@
 #include <linux/can.h>
 #include <linux/can/raw.h>
 #include <iostream>
-#include "include/status.h"
-#include "include/basic_types.h"
+#include "./include/status.h"
+#include "./include/basic_types.h"
 
 #define CANFD_START_BIT_MAX   (511)
 #define CAN_START_BIT_MAX   (63)

+ 9 - 9
src/controller/controller_Geely_xingyueL/include/socket_udp/socket_udp.h

@@ -1,6 +1,6 @@
 #ifndef SOCKET_UDP_H
 #define SOCKET_UDP_H
-#include "include/basic_types.h"
+#include "basic_types.h"
 #include <arpa/inet.h>
 #include <fcntl.h>
 #include <iostream>
@@ -19,9 +19,9 @@
 
 struct DGram_VehicleStatus
 {
-    short m_gram_header;   // 报文头 0xAAA
-    short m_gram_id;       // 报文标识 0xAF1
-    short m_vehicle_id;    // 车辆ID 0x00A ~ 0x00C
+    short m_gram_header{0xAAA};   // 报文头 0xAAA
+    short m_gram_id{0xAF1};       // 报文标识 0xAF1
+    short m_vehicle_id{0x00A};    // 车辆ID 0x00A ~ 0x00C
     short m_speed;         // 速度
     int m_steering;        // 方向盘转角 正常上报系数[-540,540], unit:1degree
     short m_gear;          // 档位 P:1 ,R:2, N:3, D:4
@@ -50,9 +50,9 @@ struct DGram_VehicleStatus
 
 struct DGram_RemoteControl
 {
-    short m_gram_header;    // 报文头 0xA1A
-    short m_gram_id;        // 报文标识 0xA11
-    short m_vehicle_id;     // 车辆ID 0x00A ~ 0x00C
+    short m_gram_header{0xA1A};    // 报文头 0xA1A
+    short m_gram_id{0xA11};        // 报文标识 0xA11
+    short m_vehicle_id{0x00A};     // 车辆ID 0x00A ~ 0x00C
     short m_rc_acc_pedal;   // 油门开度
     short m_rc_brake_pedal; // 刹车踏板开度
     short m_rc_gear;        // 遥控档位 P:1 ,R:2, N:3, D:4
@@ -84,7 +84,7 @@ class RemoteUdpCommunication
   DGram_RemoteControl remote_control_cmd_;
 
   public:
-  bool is_rec_timeout;
+  bool is_rec_timeout{false};
 
   private:
   int socket_udp_init();
@@ -101,4 +101,4 @@ class RemoteUdpCommunication
   const uint16_t kMaxTimeForCommTimeout = 1000 / 50; // base cycle 50ms. timeout is 1000ms
 };
 
-#endif
+#endif

+ 51 - 3
src/controller/controller_Geely_xingyueL/include/status.h

@@ -10,10 +10,15 @@
 #include "decition.pb.h"
 #include "chassis.pb.h"
 #include <thread>
+#include <iostream>
+#include <fstream>
 #include "include/car_control.h"
 
 CarControl car_control_module;
 
+using namespace std;
+
+
 void * gpadecition;
 
 iv::brain::decition gdecition_def;
@@ -53,11 +58,13 @@ static void ShareChassis(void * pa,iv::chassis  * pchassis)
 
 void executeDecition(const iv::brain::decition decition)
 {
-    std::cout<<"Command: Acc is "<<decition.accelerator()<<" Angle is "<<decition.wheelangle()<<" DangWei is "<<decition.gear()<<std::endl;
+//    std::cout<<"Command: Acc is "<<decition.accelerator()<<" Angle is "<<decition.wheelangle()<<" DangWei is "<<decition.gear()<<std::endl;
 
     GearPrkgAssistReq gearSetVal= GearPrkgAssistReq::kNoRequest;
     double speedSetVal = 0;
     double EpsSetVal = 0;
+    double Steer_current_value=0;
+    Steer_current_value=car_control_module.get_current_steer_ang_in_deg();
 
     if(decition.has_gear()){
         switch (decition.gear()) {
@@ -110,6 +117,18 @@ void executeDecition(const iv::brain::decition decition)
         EpsSetVal=lastEpsSetVal;
     }
     // gearSetVal=GearPrkgAssistReq::kTargetGearD;
+
+    if(abs(EpsSetVal-Steer_current_value)<90)
+    {
+        ;
+    }
+    else
+    {
+        if(EpsSetVal-Steer_current_value>0)
+            EpsSetVal=Steer_current_value+90;
+        else
+            EpsSetVal=Steer_current_value-90;
+    }
     car_control_module.set_target_gear(gearSetVal);
     car_control_module.set_target_acc_mps2(speedSetVal);
     car_control_module.set_target_pinion_ag_in_deg(EpsSetVal);
@@ -156,7 +175,7 @@ void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned
     gdecition.CopyFrom(xdecition);
     gMutex.unlock();
     gnDecitionNum = gnDecitionNumMax;
-    std::cout<<"update decision. "<<std::endl;
+//    std::cout<<"update decision. "<<std::endl;
 }
 
 
@@ -165,17 +184,26 @@ void sendthread()
     iv::brain::decition xdecition;
 //    car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearD);
 //    car_control_module.sm_task_20ms();  // 线控状态机函数
+QTime time;
+time.start();
 
     while(1)
     {
+        int t = time.elapsed();
+        if(t > 21)
+            qDebug("%d",t);
+        time.restart();
         if(gnDecitionNum <= 0)
         {
+            gdecition_def.set_wheelangle(car_control_module.get_current_steer_ang_in_deg());
             xdecition.CopyFrom(gdecition_def);
+            std::cout<<"copy from gdecition_def@@@@@@@@@@@@"<<std::endl;
         }
         else
         {
             gMutex.lock();
             xdecition.CopyFrom(gdecition);
+            std::cout<<"copy from ADAS gdecition"<<std::endl;
             gMutex.unlock();
             gnDecitionNum--;
         }
@@ -194,7 +222,27 @@ void sendthread()
             car_control_module.set_lat_lgt_ctrl_req(true);
         }
 
-        car_control_module.sm_task_20ms();  // 线控状态机函数
+
+                       string filename="log.txt";
+                       ofstream outfile;
+                       outfile.open(filename, ostream::app);
+                       QDateTime dt2=QDateTime::currentDateTime();
+                       outfile <<dt2.time().hour()<<":"<<dt2.time().minute()<<":"<<dt2.time().second()<<":"<<dt2.time().msec()<<","
+                              <<"chasis_status"  << ","  <<(int)car_control_module.get_chassis_err_state()<< ","
+                              <<"Decide_ACC"  << ","  <<lastspeedSetVal << ","
+//                              <<"Decide_gear"<< ","  <<lastgearSetVal << ","
+//                              <<"Vehicle_RealSpd"<< ","  <<setprecision(2)<<now_gps_ins.<< ","
+                              <<"Decide_Angle"<< "," <<lastEpsSetVal << ","
+//                              <<"Vehicle_GPS_heading"<< ","<< setprecision(10)<<now_gps_ins.ins_heading_angle<< ","
+//                              <<"Vehicle_GPS_X"<< ","<< setprecision(10)<<now_gps_ins.gps_lat<< ","
+//                              <<"Vehicle_GPS_Y"<< ","<< setprecision(10)<<now_gps_ins.gps_lng<< ","
+//                              <<"Trace_Point"<< ","<<PathPoint<< ","
+//                              <<"OBS_Distance"<< ","<<obsDistance<< ","
+                              <<"machine_state"<< ","<<(int)car_control_module.get_chassis_statemachine_sts()<< ","
+                              <<endl;
+                       outfile.close();
+
+//        car_control_module.sm_task_20ms();  // 线控状态机函数
         std::this_thread::sleep_for(std::chrono::milliseconds(20));
     }
 }

+ 10 - 8
src/decition/decition_brain_sf_Jeely_xingyueL/decition/adc_adapter/jeely_xingyueL_adapter.cpp

@@ -117,14 +117,16 @@ iv::decition::Decition iv::decition::Jeely_xingyueL_adapter::getAdapterDeciton(G
     (*decition)->wheel_angle=max((float)-450.0,(*decition)->wheel_angle);
      (*decition)->wheel_angle=min((float)450.0,(*decition)->wheel_angle);
 
-    if((*decition)->accelerator>=0){
-        (*decition)->torque= (*decition)->accelerator;
-        (*decition)->brake=0;
-    }else{
-        (*decition)->torque=0;
-        (*decition)->brake=0-(*decition)->accelerator;
-    }
-
+//    if((*decition)->accelerator>=0){
+//        (*decition)->torque= (*decition)->accelerator;
+//        (*decition)->brake=0;
+//    }else{
+//        (*decition)->torque=0;
+//        (*decition)->brake=0-(*decition)->accelerator;
+//    }
+
+    (*decition)->torque= (*decition)->accelerator;
+     (*decition)->brake=0;
 
     if(ServiceCarStatus.bocheMode ||ServiceCarStatus.daocheMode){
         (*decition)->dangWei=2;