car_control.h 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  1. #ifndef CAR_CONTROL_H
  2. #define CAR_CONTROL_H
  3. #include "kx_11_can_frame/asdm_sim_canfd_frame.h"
  4. #include <thread>
  5. enum class StsMach
  6. {
  7. kStandby = 0,
  8. kApaStartup = 1,
  9. kApaShutDown = 2,
  10. kApaActive = 3,
  11. kFailure = 4,
  12. kHwaPreActive = 5,
  13. kHwaActive = 6,
  14. kHwaShutDown = 7
  15. };
  16. enum class ChassisErrCode
  17. {
  18. kNoFailure = 0,
  19. kSteeringFailure = 1,
  20. kBrakeFailure = 2,
  21. kPropulsionFailure = 3,
  22. kRbuFailure = 4,
  23. kCommunicationFailure = 5,
  24. kVDSWInternalFailure = 6,
  25. kRWSFailure = 7,
  26. kSteerWheelServiousErr = 8,
  27. kHandshakeTimeout = 9
  28. };
  29. class CarControl
  30. {
  31. public:
  32. CarControl();
  33. ~CarControl();
  34. void set_lat_lgt_ctrl_req(bool req);
  35. void set_target_gear(GearPrkgAssistReq tar);
  36. bool is_lat_lgt_ctrl_active();
  37. void set_target_pinion_ag_in_deg(float32_t ang_req);
  38. void set_target_acc_mps2(float32_t tar_acc);
  39. void set_turn_light_status(TurnLightIndicReq req);
  40. void set_ctrl_mode_switch_spd(float32_t spd_kmh);
  41. void set_debug_log_para(bool enable, uint16_t print_cycle_ms);
  42. ChassisErrCode get_chassis_err_state();
  43. StsMach get_chassis_statemachine_sts();
  44. float32_t get_current_steer_ang_in_deg();
  45. float32_t get_current_vehicle_spd_in_ms();
  46. GearPrkgAssistReq get_setted_tar_gear();
  47. GearLevelIndicate get_cur_disp_gear();
  48. private:
  49. void sm_task_20ms();
  50. void sm_task_thread();
  51. bool is_chassis_system_failure();
  52. bool is_hwa_switched();
  53. void apa_active_ctrl();
  54. void hwa_active_ctrl();
  55. bool is_target_move_gear_changed();
  56. bool is_vehicle_standstill_sts();
  57. bool is_hwa_active();
  58. void chassis_handshake_off();
  59. void apa_startup_action();
  60. void hwa_pre_active();
  61. bool is_car_vin_matched();
  62. private:
  63. std::unique_ptr<ASDM_Sim_Process> asdm_obj_ptr_{nullptr};
  64. StsMach sm_{StsMach::kStandby};
  65. std::unique_ptr<std::thread> thread_sm_task_{nullptr};
  66. bool is_chassis_handshake_timeout{false};
  67. bool is_lat_lgt_ctrl_requested_{false};
  68. GearPrkgAssistReq tar_gear_{GearPrkgAssistReq::kNoRequest};
  69. float32_t tar_pinion_ang_in_deg_{0};
  70. float32_t tar_acc_meter_per_second2_{0};
  71. uint16_t time_startup_ = 0;
  72. uint16_t timeout_apa_startup = 0;
  73. uint16_t timeout_apa_shutdown = 0;
  74. uint16_t timeout_hwa_startup = 0;
  75. uint16_t timeout_hwa_shutdown = 0;
  76. uint32_t time_vin_check = 0;
  77. const uint16_t kMaxStartupDlyTime = (3000 / 20); // uinit:ms
  78. const uint16_t kMaxApaStartupTime = (3000 / 20); // uinit:ms
  79. const uint16_t kMaxApaShutdownTime = (10000 / 20); // uinit:ms
  80. const uint16_t kMaxHwaStartupTime = (5000 / 20); // uinit:ms
  81. const uint16_t kMaxHwaShutdownTime = (10000 / 20); // uinit:ms
  82. const uint32_t kMaxVinCheckTime = (5 * 60 * 1000 / 20); // uinit:ms, 5minites
  83. float32_t kSpeedForCtrlModSwitch = CONVERT_KPH_2_MPS(6); // the APA longitude speed uppper limit is 10km/h
  84. const float32_t kSteerDiffMax = 90;
  85. const float32_t kSteerDiffMin = -90;
  86. const float32_t kSteerMaxAng = 450;
  87. const float32_t kSteerMinAng = -450;
  88. const float32_t kApaShutDownDecel = -1.28; //uinit: m/s^2, apa max deceleration.
  89. const float32_t kHwaShutDownDecel = -5; //uinit: m/s^2, hwa shutdown deceleration value.
  90. const float32_t kApaAccelerationMax = 1.27; //uinit: m/s^2
  91. const float32_t kApaAccelerationMin = -1.27; //uinit: m/s^2
  92. const float32_t kHwaAccelerationMax = 11; //uinit: m/s^2
  93. const float32_t kHwaAccelerationMin = -11; //uinit: m/s^2
  94. // debug parameter:
  95. bool debug_enable_{false};
  96. uint16_t print_period_ms_{20};
  97. };
  98. #endif