瀏覽代碼

add chassis test tool for jelly xingyueL

jinliang 2 年之前
父節點
當前提交
b5f438cbbb

+ 45 - 0
src/tool/carControlTester/carControlTester.pro

@@ -0,0 +1,45 @@
+#-------------------------------------------------
+#
+# Project created by QtCreator 2022-05-18T08:38:33
+#
+#-------------------------------------------------
+
+QT       += core gui
+
+greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
+
+TARGET = carControlTester
+TEMPLATE = app
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which has been marked as deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if you use deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+
+SOURCES += \
+        main.cpp \
+        mainwindow.cpp
+
+HEADERS += \
+    include/kx_11_can_frame/asdm_sim_canfd_data_type.h \
+    include/kx_11_can_frame/asdm_sim_canfd_frame.h \
+    include/kx_11_can_frame/can_canfd_common.h \
+    include/kx_11_can_frame/chassis_can1_frame.h \
+    include/socket_can_interface/socket_can_interface.h \
+    include/socket_udp/socket_udp.h \
+    include/basic_types.h \
+    include/car_control.h \
+    mainwindow.h \
+    include/status.h
+
+FORMS += \
+        mainwindow.ui
+
+LIBS += $$PWD/lib/libcar_control.a

+ 18 - 0
src/tool/carControlTester/include/basic_types.h

@@ -0,0 +1,18 @@
+/* *
+ * FUNCTION: Define Common Types
+ * */
+
+#ifndef BASIC_TYPES_H
+#define BASIC_TYPES_H
+#include <stdint.h>
+
+/* * Define basic numerical types.
+* MISRA Rule 3-9-2 typedefs that indicate size and signedness should be
+* used in place of the basic numerical types.
+*/
+typedef char char_t;
+typedef float float32_t;
+typedef double float64_t;
+typedef long double float128_t;
+
+#endif // BASIC_TYPES_H

+ 96 - 0
src/tool/carControlTester/include/car_control.h

@@ -0,0 +1,96 @@
+#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"
+
+enum class StsMach
+{
+  kStandby = 0,
+  kApaStartup = 1,
+  kApaShutDown = 2,
+  kApaActive = 3,
+  kFailure = 4,
+  kHwaPreActive = 5,
+  kHwaActive = 6,
+  kHwaShutDown = 7
+};
+
+enum class ChassisErrCode
+{
+  kNoFailure = 0,
+  kSteeringFailure = 1,
+  kBrakeFailure = 2, 
+  kPropulsionFailure = 3,
+  kRbuFailure = 4,
+  kCommunicationFailure = 5,
+  kVDSWInternalFailure = 6,
+  kRWSFailure = 7,
+  kSteerWheelServiousErr = 8,
+  kHandshakeTimeout = 9
+};
+
+class CarControl
+{
+public:
+  CarControl();
+  ~CarControl();
+
+  void sm_task_20ms();
+
+  void set_lat_lgt_ctrl_req(bool req);
+  void set_target_gear(GearPrkgAssistReq tar);
+  bool is_lat_lgt_ctrl_active();
+  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);
+  ChassisErrCode get_chassis_err_state();
+  StsMach get_chassis_statemachine_sts();
+  float32_t get_current_steer_ang_in_deg();
+  float32_t get_current_vehicle_spd_in_ms();
+  GearPrkgAssistReq get_setted_tar_gear();
+  GearLevelIndicate get_cur_disp_gear();
+private:
+  bool is_chassis_system_failure();
+  bool is_hwa_switched();
+  void apa_active_ctrl();
+  void hwa_active_ctrl();
+  bool is_target_move_gear_changed();
+  bool is_vehicle_standstill_sts();
+  bool is_hwa_active();
+  void chassis_handshake_off();
+  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;
+
+  bool is_lat_lgt_ctrl_requested_;
+  GearPrkgAssistReq tar_gear_;
+  float32_t tar_pinion_ang_in_deg_;
+  float32_t tar_acc_meter_per_second2_;
+
+  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
+  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.
+};
+
+#endif

+ 333 - 0
src/tool/carControlTester/include/kx_11_can_frame/asdm_sim_canfd_data_type.h

@@ -0,0 +1,333 @@
+#ifndef ASDM_CANFD4_DATA_H
+#define ASDM_CANFD4_DATA_H
+
+#include "can_canfd_common.h"
+
+
+// PAS Frame01
+enum class PrkgStandStillReq
+{
+  kNotRequested = 0,
+  kRequested = 1
+};
+
+enum class PrkgBrakeFctMode
+{
+  kDefault = 0,
+  kComfortable = 1,
+  kEmergency = 2
+};
+
+enum class PrkgEpbReq
+{
+  kNoRequest = 0,
+  kReleaseRequest = 1,
+  kApplyRequest = 2,
+  kReserverd = 3
+};
+
+enum class PrkgCtrlModReq
+{
+  kNoRequest = 0,
+  kApaRequest = 1,
+  kRpaRequest = 2,
+  kHpaRequest = 3,
+  kApaControlActive = 4,
+  kRpaControlActive = 5,
+  kHpaControlActive = 6,
+  kReversed2 = 7
+};
+
+enum class AsyLatCtrlModReq
+{
+  kNoReq = 0,
+  kHighWayAssist = 1,
+  kEmgyLkaForObjRe = 2,
+  kEmgyLkaForStat = 3,
+  kSftyLka = 4,
+  kSteerAssc = 5,
+  kReserverd1 = 6,
+  kReserverd2 = 7,
+  kReserverd3 = 8,
+  kEmgyManvAssi = 9,
+  kReserverd4 = 10,
+  kReserverd5 = 11,
+  kSHWA = 12,
+  kAPA = 13,
+  kRPA = 14,
+  kHPA = 15
+};
+
+enum class AsyALgtCtrlModReq
+{
+  kNoReq = 0,
+  kAPA = 11,
+  kPEB = 10,
+  kHPA = 13,
+  kRPA = 12,
+};
+
+enum class RpaAuthentReq
+{
+  kSuccess = 0,
+  kFailed = 1,
+  kNone = 2,
+  kReserverd = 3
+};
+
+enum class GearPrkgAssistReq
+{
+  kNoRequest = 0,
+  kTargetGearP = 1,
+  kTargetGearR = 2,
+  kTargetGearD = 3
+};
+
+enum class PrkgEngRunngReq
+{
+  kDefault = 0,
+  kStopInhibited = 1,
+  kRequestToKeepEngRun = 2,
+  kReserved = 3
+};
+
+enum class PrkgEcuType
+{
+  kPAS1 = 0,
+  kPAS2 = 1,
+  kPAS3 = 2
+};
+
+
+// PAS Frame18
+enum class PrkgFctVmmDriveModReq
+{
+  kNo = 0,
+  kYes = 1
+};
+
+struct PasFr18Signals
+{
+  PrkgFctVmmDriveModReq vmm_drive_mod_req;
+};
+
+// PAS Frame20
+enum class DriveAssistSysSts
+{
+  kOff = 0,
+  kStandby = 1,
+  kFailure = 2,
+  kSearching = 3,
+  kParkingProcessActive = 4,
+  kParkingPrecessCompleted = 5,
+  kQuit = 6,
+  kSuspend = 7,
+  kAbort = 8,
+  kPreParkingProcessActive = 9
+};
+
+struct PasFr20Signals
+{
+  DriveAssistSysSts drive_assist_sys_sts;
+};
+
+
+// Asdm Frame01
+enum class VehicleMoveStatus
+{
+  kUnknown = 0,
+  kStandstillVal1 = 1,
+  kStandstillVal2 = 2,
+  kStandstillVal3 = 3,
+  kRollFowardVal1 = 4,
+  kRollFowardVal2 = 5,
+  kRollBackwardVal1 = 6,
+  kRollBackwardVal2 = 7
+};
+
+enum class StandstillStsForHld
+{
+  kHldVal0 = 0,
+  kHldVal1 = 1,
+  kHldVal2 = 2,
+  kHldVal3 = 3,
+  kHldVal4 = 4,
+  kHldVal5 = 5,
+  kHldVal6 = 6,
+  kHldVal7 = 7
+};
+
+enum class PrkgLatLgtFailr
+{
+  kNoFailure = 0,
+  kSteeringFailure = 1,
+  kBrakeFailure = 2, 
+  kPropulsionFailure = 3,
+  kRbuFailure = 4,
+  kCommunicationFailure = 5,
+  kVDSWInternalFailure = 6,
+  kRWSFailure = 7
+};
+
+enum class EngineWorkStatus
+{
+  kInit = 0,
+  kAwake = 1,
+  kReady = 2,
+  kPreStarting = 3,
+  kStartInProgress = 4,
+  kRunning = 5,
+  kRunningStandby = 6,
+  kRunningStrtgInProgs = 7,
+  kRunningRemStrtd = 8,
+  kAfterRun = 9
+};
+
+// Asdm Frame02
+enum class CarModeSts
+{
+  kNorm = 0,
+  kTransport = 1,
+  kFactory = 2,
+  kCrash = 3,
+  kDyno = 4,
+};
+
+enum class UsageModeSts
+{
+  kAbandond = 0,
+  kInactive = 1,
+  kConvenious = 2,
+  kActive = 0xb,
+  kDriving = 0xd
+};
+
+enum class GearLevelIndicate
+{
+  kPark = 0,
+  kReverse = 1,
+  kNeutro = 2,
+  kDrive = 3,
+  kManMode = 4,
+  kReserverd1 = 5,
+  kReserverd2 = 6,
+  kUndefined = 7
+};
+
+enum class EpbStatus
+{
+  kAllApplied = 0x3,
+  kAllInTrans = 0x5,
+  kActuatorAllReleased = 0x9,
+  kBrakeDynDegraded = 0xA,
+  kBrakeDyn = 0xC,
+  kError = 0xF
+};
+
+enum class BrakePedalPosition
+{
+  kNoPressed = 0,
+  kPressed = 1
+};
+
+enum class CfmdLatCtrlMod
+{
+  kNoReq = 0,
+  kHighWayAssist = 1,
+  kEmgyLkaRear = 2,
+  kEmgyLkaStart = 3,
+  kSafetyLKA = 4,
+  kSteerAssist = 5,
+  kDsrOverSteer = 6,
+  kDsrMueSplit = 7,
+  kDsrTrlrStaby = 8,
+  kEmgyManvAssi = 9,
+  kReserverd1 = 0xA,
+  kReserverd2 = 0xB,
+  kSHWA = 0xC,
+  kAPA = 0xD,
+  kRPA = 0xE,
+  kHPA = 0xF
+};
+
+enum class CfmdLgtCtrlMod
+{
+  kNoReq = 0,
+  kPEB = 0xA,
+  kAPA = 0xB,
+  kPRA = 0xC,
+  kHPA = 0xD
+};
+
+enum class AccStatus
+{
+  kReserverd1 = 0,
+  kStandby = 1,
+  kActive = 2,
+  kReserverd2 = 3,
+  kOverride = 4,
+  kStandActive = 5,
+  kStandWait = 6,
+  kTempFailure = 7,
+  kPermanentFailure = 8,
+  kReserverd3 = 9
+};
+
+enum class TurnLightIndicReq
+{
+  kOff = 0,
+  kLeft = 1,
+  kRight = 2
+};
+
+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;
+};
+
+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;
+};
+
+#endif

+ 77 - 0
src/tool/carControlTester/include/kx_11_can_frame/asdm_sim_canfd_frame.h

@@ -0,0 +1,77 @@
+#ifndef ASDM_CANFD4_FRAME_H
+#define ASDM_CANFD4_FRAME_H
+
+#include "include/socket_can_interface/socket_can_interface.h"
+#include "can_canfd_common.h"
+#include "asdm_sim_canfd_data_type.h"
+
+// define CAN initial parameters
+
+#define ASDM_SIM_CANFD_BITRATE (500000)
+#define ASDM_SIM_CANFD_DBITRATE (2000000)
+
+
+class ASDM_Sim_Process : public SocketCanInterface
+{
+public:
+  ASDM_Sim_Process();
+  ~ASDM_Sim_Process();
+
+public:
+
+  ReceiveFrameCanfd vddm_fr03_;
+  ReceiveFrameCanfd bcm_fr00_;
+  ReceiveFrameCanfd bcm_fr03_;
+  ReceiveFrameCanfd bcm_fr06_;
+
+  AsdmControlRequest asdm_control_request;
+  VddmFeedback vddm_feedback;
+private:
+  void receive_process(canfd_frame receive_frame);
+  static void* tx_rx_polling(void* arg);
+  static void* rx_5ms(void* arg);
+  static void* tx_5ms(void* arg);
+  void set_filters();
+  void vddm_fr03_decode(void);
+  void bcm_fr00_decode(void);
+  void bcm_fr03_decode(void);
+  void bcm_fr06_decode(void);
+
+  void asdm_sim_fr03_frame_send(void);
+  void asdm_sim_fr02_frame_send(void);
+  void asdm_sim_fr04_frame_send(void);
+  void asdm_sim_fr11_frame_send(void);
+  void asdm_sim_fr30_frame_send(void);
+  void asdm_sim_nm_frame_send(void);
+  void asdm_sim_fr20_frame_send(void);
+  void asdm_sim_fr10_frame_send(void);
+  void asdm_sim_fr13_frame_send(void);
+
+private:
+  SendFrameCanfd asdm_sim_fr02_;
+  SendFrameCanfd asdm_sim_fr03_;
+  SendFrameCanfd asdm_sim_fr04_;
+  SendFrameCanfd asdm_sim_fr11_;
+  SendFrameCanfd asdm_sim_fr30_;
+  SendFrameCanfd asdm_sim_nm_fr_;
+  SendFrameCanfd asdm_sim_fr20_;
+  SendFrameCanfd asdm_sim_fr10_;
+  SendFrameCanfd asdm_sim_fr13_;
+
+  pthread_mutex_t mtx_asdm_sim_fr02_;
+  pthread_mutex_t mtx_asdm_sim_fr03_;
+  pthread_mutex_t mtx_asdm_sim_fr04_;
+  pthread_mutex_t mtx_asdm_sim_fr11_;
+  pthread_mutex_t mtx_asdm_sim_fr30_;
+  pthread_mutex_t mtx_asdm_sim_nm_fr_;
+  pthread_mutex_t mtx_asdm_sim_fr20_;
+  pthread_mutex_t mtx_asdm_sim_fr10_;
+  pthread_mutex_t mtx_asdm_sim_fr13_;
+
+  pthread_mutex_t mtx_vddm_fr03_;
+  pthread_mutex_t mtx_bcm_fr00_;
+  pthread_mutex_t mtx_bcm_fr03_;
+  pthread_mutex_t mtx_bcm_fr06_;
+};
+
+#endif

+ 91 - 0
src/tool/carControlTester/include/kx_11_can_frame/can_canfd_common.h

@@ -0,0 +1,91 @@
+#ifndef CAN_CANFD_COMMON_H
+#define CAN_CANFD_COMMON_H
+
+#include <pthread.h>
+#include "include/socket_can_interface/socket_can_interface.h"
+
+
+#define DOMAIN_ECU_PASSWORD "nvidia"
+#define ASDM_SIM_CANFD_NAME "can1"
+#define CHASSIS_CAN1_NAME "can0"
+
+
+#define PI (3.1415926)
+#define CONVERT_RAD_2_DEG(rad)  ((float64_t)rad * 180 / PI)
+#define CONVERT_DEG_2_RAD(deg)  ((float64_t)deg * PI / 180)
+#define CONVERT_KPH_2_MPS(kph)  ((float32_t)kph / 3.6)
+#define CONVERT_MPS_2_KPH(ms)   ((float32_t)ms * 3.6)
+
+
+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
+} ReceiveFrame;
+
+typedef struct
+{
+  /* data */
+  can_frame fr;       // can frame 
+  bool need_send;  // 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
+} 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
+} SendFrameCanfd;
+
+enum class GenQf1
+{
+  kUndefinedDataAccur = 0,
+  kTmpUndefdData = 1,
+  kDataAccurNotWithinSpcn = 2,
+  kAccurData = 3
+};
+
+
+#endif

+ 107 - 0
src/tool/carControlTester/include/kx_11_can_frame/chassis_can1_frame.h

@@ -0,0 +1,107 @@
+#ifndef CHASSIS_CAN1_FRAME_H
+#define CHASSIS_CAN1_FRAME_H
+
+#include "include/socket_can_interface/socket_can_interface.h"
+#include "can_canfd_common.h"
+
+
+#define CHASSIS_CAN1_BITRATE (500000)
+
+enum class SteerStsToParkAssis
+{
+  kNormOper = 0,
+  kAbortBySpdHi = 1,
+  kCtrlDifHi = 2,
+  kCtrlIntErr = 3,
+  kAbortByDrvIntv = 4,
+  kSteerTqHi = 5,
+  kSpare1 = 6,
+  kSpare2 = 7
+};
+
+enum class DrvrWheelHoldSts
+{
+  kNoInfo = 0,
+  kOffDetected = 1,
+  kNotOnOrOffDetected = 2,
+  kOnDetected = 3
+};
+
+struct AccFuncPinionCtrReq
+{
+  float32_t torque_upper_limit;
+  float32_t torque_lower_limit;
+  float32_t pinion_ang_req_in_deg;
+};
+
+
+
+class ChassisCAN1_Process : public SocketCanInterface
+{
+public:
+  ChassisCAN1_Process();
+  ~ChassisCAN1_Process();
+  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;
+  
+  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;
+
+  // input parameters
+  float32_t pas_pinion_ang_req_in_deg;
+  bool is_pas_func_active;
+  struct AccFuncPinionCtrReq acc_func_pinion_ctrl_req;
+
+private:
+  static void* chassis_tx_rx_polling(void* arg);
+  static void* chassis_rx_5ms(void* arg);
+  static void* chassis_tx_15ms(void* arg);
+  static void* chassis_asdm_tx(void* arg);
+  void receive_process(can_frame receive_frame);
+  void pscm_fr03_decode(void);
+  void pscm_fr07_decode(void);
+  void vddm_fr21_decode(void);
+  void pscm_fr01_decode(void);
+  void pscm_fr02_decode(void);
+
+  void pas_fr02_frame_send(void);
+  void pas_fr04_frame_send(void);
+  void pas_nm_frame_send(void);
+  void asdm_fr01_frame_send(void);
+  void asdm_fr03_frame_send(void);
+
+private:
+  ReceiveFrame pscm_chas1_fr03_;
+  ReceiveFrame pscm_chas1_fr07_;
+  ReceiveFrame pscm_chas1_fr01_;
+  ReceiveFrame pscm_chas1_fr02_;
+  ReceiveFrame vddm_chas1_fr21_;
+
+  SendFrame pas_chas1_fr02_;
+  SendFrame pas_chas1_fr04_;
+  SendFrame pas_chas1_nmfr_;
+  SendFrame asdm_chas1_fr01_;
+  SendFrame asdm_chas1_fr03_;
+
+  pthread_mutex_t mtx_pscm_chas1_fr03_;
+  pthread_mutex_t mtx_pscm_chas1_fr07_;
+  pthread_mutex_t mtx_pscm_chas1_fr01_;
+  pthread_mutex_t mtx_pscm_chas1_fr02_;
+  pthread_mutex_t mtx_vddm_chas1_fr21_;
+
+  pthread_mutex_t mtx_pas_chas1_fr02_;
+  pthread_mutex_t mtx_asdm_chas1_fr01_;
+  pthread_mutex_t mtx_asdm_chas1_fr03_;
+};
+
+#endif

+ 85 - 0
src/tool/carControlTester/include/socket_can_interface/socket_can_interface.h

@@ -0,0 +1,85 @@
+/*
+* Copyright (c) GEELY . 2021-2021. All rights reserved.
+* Description: socket can interface declaration
+*/
+
+#ifndef SOCKET_CAN_INTERFACE_H
+#define SOCKET_CAN_INTERFACE_H
+
+#include <string>
+#include <string.h>
+#include <vector>
+#include <unistd.h>
+#include <net/if.h>
+#include <sys/ioctl.h>
+#include <sys/socket.h>
+#include <linux/can.h>
+#include <linux/can/raw.h>
+#include <iostream>
+#include "include/status.h"
+#include "include/basic_types.h"
+
+#define CANFD_START_BIT_MAX   (511)
+#define CAN_START_BIT_MAX   (63)
+#define SIG_BIT_LEN_MAX     (32)    // can and canfd , the signals max lenght shall be less or equal than 32bit.
+
+#define BYTE_BITS_NUM   (8)
+
+typedef std::vector<uint8_t> Crc8_buf;
+#define CAST_U32(data) static_cast<uint32_t>(data)
+
+typedef struct
+{
+    uint16_t msb_start_bit;
+    uint8_t bit_len;
+    float64_t factor;
+    float32_t offset;
+} SignalAttribute;
+
+class SocketCanInterface
+{
+public:
+    SocketCanInterface() = default;
+    ~SocketCanInterface() = default;
+
+    bool Init(const std::string &canDevice, const std::uint32_t &bitRate, const std::string &passWord,  const std::uint32_t &dbitRate = 0); // data bit rate default 0 : mean the can is CAN, set the dbitrate mean CANFD!
+    bool SetRecvTimeout(const struct timeval &tv) const;
+    bool SetCanFiLter(const struct can_filter &filter) const;
+    bool SetCanFilters(const std::vector<can_filter> &filters) const;
+    std::int32_t ReadCan(canfd_frame &receiveFrame, bool &isCanFrame) const;
+    std::int32_t ReadCan(can_frame &receiveFrame) const;
+    std::int32_t WriteCan(const canfd_frame &sendFrame) const;
+    std::int32_t WriteCan(const can_frame &sendFrame) const;
+    can_frame GetCanFrameFrom(canfd_frame* receiveFrame) const;
+    
+    uint8_t GetCRC_8(const std::vector<uint8_t> &crc8_data);
+    void PushUnsignedSignal(std::vector<uint8_t> &crc8_data, uint32_t phy_val, const SignalAttribute &attr);
+    void PushUnsignedSignal(std::vector<uint8_t> &crc8_data, float64_t phy_val, const SignalAttribute &attr);
+    void PushDataId(std::vector<uint8_t> &crc8_data, uint16_t data_id);
+
+    uint32_t GetUnsignedSignalRawData(const can_frame &rec_can_frame, const SignalAttribute &sig_attr);
+    uint32_t GetUnsignedSignalRawData(const canfd_frame &rec_canfd_frame, const SignalAttribute &sig_attr);
+    int32_t GetSignedSignalRawData(const can_frame &rec_can_frame, const SignalAttribute &sig_attr);
+    int32_t GetSignedSignalRawData(const canfd_frame &rec_canfd_frame, const SignalAttribute &sig_attr);
+    void SetUnsignedSignalRawData(can_frame &send_can_frame, const SignalAttribute &sig_attr, const uint32_t signal_raw);
+    void SetUnsignedSignalRawData(canfd_frame &send_canfd_frame, const SignalAttribute &sig_attr, const uint32_t signal_raw);
+    void SetSignedSignalRawData(can_frame &send_can_frame, const SignalAttribute &sig_attr, const int32_t signal_raw);
+    void SetSignedSignalRawData(canfd_frame &send_canfd_frame, const SignalAttribute &sig_attr, const int32_t signal_raw);
+
+    void SetUnsignedSignalPhyData(canfd_frame &send_canfd_frame, const SignalAttribute &sig_attr, const float32_t signal_phy);
+    void SetUnsignedSignalPhyData(can_frame &send_can_frame, const SignalAttribute &sig_attr, const float64_t signal_phy);
+    void cntr_inc(uint32_t &cntr);
+private:
+    void CloseSocketCan();
+    uint32_t GetUnsignedData(const uint8_t* buf, const SignalAttribute &sig_attr);
+    int32_t GetSignedData(const uint8_t* buf, const SignalAttribute &sig_attr);
+    void SetUnsignedData(uint8_t* buf, const SignalAttribute &sig_attr, const uint32_t signal_raw);
+    void SetSignedData(uint8_t* buf, const SignalAttribute &sig_attr, const int32_t signal_raw);
+
+private:
+    int32_t m_sockCan = -1;
+    bool is_canfd_mode = false;
+    std::string dev_name;
+};
+
+#endif

+ 104 - 0
src/tool/carControlTester/include/socket_udp/socket_udp.h

@@ -0,0 +1,104 @@
+#ifndef SOCKET_UDP_H
+#define SOCKET_UDP_H
+#include "include/basic_types.h"
+#include <arpa/inet.h>
+#include <fcntl.h>
+#include <iostream>
+#include <math.h>
+#include <netinet/in.h>
+#include <pthread.h>
+#include <sstream>
+#include <string.h>
+#include <sys/socket.h>
+#include <unistd.h>
+
+// define the socket UDP communication IP and Ports
+#define UDP_SEND_TARGET_IP_STRING "192.168.4.132"
+#define UDP_SEND_TARGET_PORT      8111
+#define LOCAL_UDP_RECEIVE_PORT    8111
+
+struct DGram_VehicleStatus
+{
+    short m_gram_header;   // 报文头 0xAAA
+    short m_gram_id;       // 报文标识 0xAF1
+    short m_vehicle_id;    // 车辆ID 0x00A ~ 0x00C
+    short m_speed;         // 速度
+    int m_steering;        // 方向盘转角 正常上报系数[-540,540], unit:1degree
+    short m_gear;          // 档位 P:1 ,R:2, N:3, D:4
+    short m_rpm;           // 发动机转速 基准值14000,所以上报的时候减了14000
+    short m_vehicle_state; // 2021-5-17 用作表示底层车辆can数据是否正常上报 0:故障 1:正常;
+    short m_epb_release_status;     // 0 : epb released 1 : epb applied
+    short m_ctrl_info;     // 反馈给界面的车辆状态。 控制状态 0:未被接管; 1:被接管; 2:遥控中被人工接管
+    short m_release_feedback;
+    int m_lat;
+    int m_lon;
+    short m_heading;
+    short m_FL_door;
+    short m_FR_door;
+    short m_RL_door;
+    short m_RR_door;
+    short m_electricity;
+    short m_FL_window;
+    short m_FR_window;
+    short m_RL_window;
+    short m_RR_window;
+    short m_start_state;
+    short m_light; //车辆灯光状态 0:关闭 1:近光 2:远光 3:左 4;右
+    short m_wiper; //雨刷状态开关 0:关闭 1:1挡 2:2挡 3:3挡
+    short m_truck; //后备箱车锁状态0:未上锁 1:上锁
+};
+
+struct DGram_RemoteControl
+{
+    short m_gram_header;    // 报文头 0xA1A
+    short m_gram_id;        // 报文标识 0xA11
+    short m_vehicle_id;     // 车辆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
+    short m_rc_speed;       // 遥控速度
+    short m_ctrl_sign;      // 遥控状态, 1: 遥控; 0: 自动
+    int m_rc_steer;         // 遥控方向盘转角  [-540,540] 左正右负。 receive steer angle unit is 1degree
+    short m_rc_ctrl_sign;   // 不用
+    short m_rc_Door_lock;
+    short m_rc_window_up;
+    short m_rc_window_down;
+    short m_rc_start;
+    short m_rc_trumpet;
+    short m_rc_light;
+    short m_rc_wiper;
+    short m_rc_trunk;
+    short m_rc_both_light;
+    short m_rc_epb; //电子手刹
+};
+
+
+class RemoteUdpCommunication
+{
+  public:
+  RemoteUdpCommunication();
+  ~RemoteUdpCommunication();
+
+  public:
+  DGram_VehicleStatus vehicle_upload_status_;
+  DGram_RemoteControl remote_control_cmd_;
+
+  public:
+  bool is_rec_timeout;
+
+  private:
+  int socket_udp_init();
+  static void* socket_send(void* arg);
+  static void* socket_receive(void* arg);
+  void close_socket_udp();
+  void setnonblocking(int sock);
+  private:
+  struct sockaddr_in socksend_addr_;
+  struct sockaddr_in sockrcv_addr_;
+  int send_fd_ = -1;
+  int receive_fd_ = -1;
+  uint16_t timer_comm_timeout_cnt = 0;
+  const uint16_t kMaxTimeForCommTimeout = 1000 / 50; // base cycle 50ms. timeout is 1000ms
+};
+
+#endif

+ 12 - 0
src/tool/carControlTester/include/status.h

@@ -0,0 +1,12 @@
+/* *
+ * FUNCTION: Define Status
+ *    */
+#ifndef _STATUS_H__
+#define _STATUS_H__
+
+#define OPERATE_OK      (0)
+#define OPERATE_NOK     (-1)
+#define DO_NOTHING()    
+
+
+#endif // _STATUS_H__

+ 11 - 0
src/tool/carControlTester/main.cpp

@@ -0,0 +1,11 @@
+#include "mainwindow.h"
+#include <QApplication>
+
+int main(int argc, char *argv[])
+{
+    QApplication a(argc, argv);
+    MainWindow w;
+    w.show();
+
+    return a.exec();
+}

+ 216 - 0
src/tool/carControlTester/mainwindow.cpp

@@ -0,0 +1,216 @@
+#include "mainwindow.h"
+#include "ui_mainwindow.h"
+
+
+MainWindow::MainWindow(QWidget *parent) :
+    QMainWindow(parent),
+    ui(new Ui::MainWindow)
+{
+    ui->setupUi(this);
+    car_control_module.set_lat_lgt_ctrl_req(false);
+    car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearP);
+    car_control_module.sm_task_20ms();
+    QTimer * timer = new QTimer();
+    connect(timer,SIGNAL(timeout()),this,SLOT(onTimer()));
+    timer->setTimerType(Qt::PreciseTimer);
+    timer->start(200);
+}
+
+MainWindow::~MainWindow()
+{
+    car_control_module.set_lat_lgt_ctrl_req(false);
+    car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearP);
+    delete ui;
+}
+
+void MainWindow::on_cBox_Handshake_clicked(bool checked)
+{
+    car_control_module.set_lat_lgt_ctrl_req(checked);
+    ui->cBoxGearD->setEnabled(checked);
+    ui->cBoxGearR->setEnabled(checked);
+    ui->cBoxGearP->setEnabled(checked);
+    ui->cBoxLampR->setEnabled(checked);
+    ui->cBoxLampL->setEnabled(checked);
+    ui->cBoxLampH->setEnabled(checked);
+    ui->sBoxEpsSet->setEnabled(checked);
+    ui->sBoxSpeedSet->setEnabled(checked);
+    ui->vSliderEpsSet->setEnabled(checked);
+    ui->vSliderSpeedSet->setEnabled(checked);
+}
+
+void MainWindow::on_cBoxGearD_clicked(bool checked)
+{
+    if(checked)
+    {
+        car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearD);
+        ui->cBoxGearP->setChecked(false);
+        ui->cBoxGearR->setChecked(false);
+    }
+    else
+    {
+        car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearP);
+        ui->cBoxGearD->setChecked(false);
+        ui->cBoxGearR->setChecked(false);
+        ui->cBoxGearP->setChecked(true);
+    }
+}
+
+void MainWindow::on_cBoxGearR_clicked(bool checked)
+{
+    if(checked)
+    {
+        car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearR);
+        ui->cBoxGearP->setChecked(false);
+        ui->cBoxGearD->setChecked(false);
+    }
+    else
+    {
+        car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearP);
+        ui->cBoxGearD->setChecked(false);
+        ui->cBoxGearR->setChecked(false);
+        ui->cBoxGearP->setChecked(true);
+    }
+}
+
+void MainWindow::on_cBoxGearP_clicked(bool checked)
+{
+    car_control_module.set_target_gear(GearPrkgAssistReq::kTargetGearP);
+    ui->cBoxGearP->setChecked(true);
+    if(checked)
+    {
+        ui->cBoxGearD->setChecked(false);
+        ui->cBoxGearR->setChecked(false);
+    }
+}
+
+void MainWindow::on_cBoxLampL_clicked(bool checked)
+{
+    if(checked)
+    {
+        car_control_module.set_turn_light_status(TurnLightIndicReq::kLeft);
+        ui->cBoxLampR->setChecked(false);
+        ui->cBoxLampH->setChecked(false);
+    }
+    else
+    {
+        car_control_module.set_turn_light_status(TurnLightIndicReq::kOff);
+        ui->cBoxLampL->setChecked(false);
+        ui->cBoxLampR->setChecked(false);
+        ui->cBoxLampH->setChecked(true);
+    }
+}
+
+void MainWindow::on_cBoxLampR_clicked(bool checked)
+{
+    if(checked)
+    {
+        car_control_module.set_turn_light_status(TurnLightIndicReq::kRight);
+        ui->cBoxLampL->setChecked(false);
+        ui->cBoxLampH->setChecked(false);
+    }
+    else
+    {
+        car_control_module.set_turn_light_status(TurnLightIndicReq::kOff);
+        ui->cBoxLampL->setChecked(false);
+        ui->cBoxLampR->setChecked(false);
+        ui->cBoxLampH->setChecked(true);
+    }
+}
+
+void MainWindow::on_cBoxLampH_clicked(bool checked)
+{
+    car_control_module.set_turn_light_status(TurnLightIndicReq::kOff);
+    ui->cBoxLampH->setChecked(true);
+    if(checked)
+    {
+        ui->cBoxLampL->setChecked(false);
+        ui->cBoxLampR->setChecked(false);
+    }
+}
+
+void MainWindow::on_sBoxSpeedSet_valueChanged(double arg1)
+{
+    car_control_module.set_target_acc_mps2(arg1);
+    ui->vSliderSpeedSet->setValue(int(arg1));
+}
+
+void MainWindow::on_vSliderSpeedSet_valueChanged(int value)
+{
+    car_control_module.set_target_acc_mps2(double(value));
+    ui->sBoxSpeedSet->setValue(double(value));
+}
+
+void MainWindow::on_sBoxEpsSet_valueChanged(double arg1)
+{
+    car_control_module.set_target_pinion_ag_in_deg(arg1);
+    ui->vSliderEpsSet->setValue(int(arg1));
+}
+
+void MainWindow::on_vSliderEpsSet_valueChanged(int value)
+{
+    car_control_module.set_target_pinion_ag_in_deg(double(value));
+    ui->sBoxEpsSet->setValue(double(value));
+}
+
+void MainWindow::onTimer()
+{
+    bool status;
+    GearPrkgAssistReq gearSetVal;
+    GearLevelIndicate gearRealVal;
+    ChassisErrCode chassErr;
+    StsMach stsMach;
+    float steerDeg, speed;
+
+    status = car_control_module.is_lat_lgt_ctrl_active();
+    if (status)
+        ui->lineEHandSake->setText("true");
+    else
+        ui->lineEHandSake->setText("false");
+
+    gearSetVal = car_control_module.get_setted_tar_gear();
+    switch (gearSetVal) {
+    case GearPrkgAssistReq::kNoRequest :
+        ui->lineESetGear->setText("N");
+        break;
+    case GearPrkgAssistReq::kTargetGearD :
+        ui->lineESetGear->setText("D");
+        break;
+    case GearPrkgAssistReq::kTargetGearP :
+        ui->lineESetGear->setText("P");
+        break;
+    case GearPrkgAssistReq::kTargetGearR :
+        ui->lineESetGear->setText("R");
+        break;
+    default:
+        ui->lineESetGear->setText("-");
+        break;
+    }
+
+    gearRealVal = car_control_module.get_cur_disp_gear();
+    switch (gearRealVal) {
+    case GearLevelIndicate::kManMode :
+        ui->lineECurGear->setText("Man");
+        break;
+    case GearLevelIndicate::kDrive :
+        ui->lineECurGear->setText("Auto");
+        break;
+    case GearLevelIndicate::kPark :
+        ui->lineECurGear->setText("Park");
+        break;
+    case GearLevelIndicate::kNeutro :
+        ui->lineECurGear->setText("Neutro");
+        break;
+    default:
+        ui->lineECurGear->setText("Reserved");
+        break;
+    }
+    int tmp1[10] = {0,1,2,3,4,5,6,7,8,9};
+    chassErr = car_control_module.get_chassis_err_state();
+    ui->lineEChaissErr->setText(QString::number(tmp1[static_cast<int>(chassErr)]));
+    stsMach = car_control_module.get_chassis_statemachine_sts();
+    ui->lineEMachErr->setText(QString::number(tmp1[static_cast<int>(stsMach)]));
+    speed = car_control_module.get_current_vehicle_spd_in_ms();
+    ui->lineESpeed->setText(QString::number(speed));
+    steerDeg = car_control_module.get_current_steer_ang_in_deg();
+    ui->lineEEPS->setText(QString::number(steerDeg));
+}

+ 52 - 0
src/tool/carControlTester/mainwindow.h

@@ -0,0 +1,52 @@
+#ifndef MAINWINDOW_H
+#define MAINWINDOW_H
+
+#include <QMainWindow>
+#include <QTimer>
+#include "include/car_control.h"
+
+namespace Ui {
+class MainWindow;
+}
+
+class MainWindow : public QMainWindow
+{
+    Q_OBJECT
+
+public:
+    explicit MainWindow(QWidget *parent = 0);
+    ~MainWindow();
+
+private slots:
+    void on_cBox_Handshake_clicked(bool checked);
+
+    void on_cBoxGearD_clicked(bool checked);
+
+    void on_cBoxGearR_clicked(bool checked);
+
+    void on_cBoxGearP_clicked(bool checked);
+
+    void on_cBoxLampL_clicked(bool checked);
+
+    void on_cBoxLampR_clicked(bool checked);
+
+    void on_cBoxLampH_clicked(bool checked);
+
+    void on_sBoxSpeedSet_valueChanged(double arg1);
+
+    void on_sBoxEpsSet_valueChanged(double arg1);
+
+    void on_vSliderSpeedSet_valueChanged(int value);
+
+    void on_vSliderEpsSet_valueChanged(int value);
+
+    void onTimer();
+
+private:
+    Ui::MainWindow *ui;
+
+    CarControl car_control_module;
+
+};
+
+#endif // MAINWINDOW_H

+ 414 - 0
src/tool/carControlTester/mainwindow.ui

@@ -0,0 +1,414 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>MainWindow</class>
+ <widget class="QMainWindow" name="MainWindow">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>531</width>
+    <height>530</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>MainWindow</string>
+  </property>
+  <widget class="QWidget" name="centralWidget">
+   <widget class="QTextBrowser" name="textBrLog">
+    <property name="geometry">
+     <rect>
+      <x>10</x>
+      <y>340</y>
+      <width>511</width>
+      <height>151</height>
+     </rect>
+    </property>
+   </widget>
+   <widget class="QGroupBox" name="groupBox">
+    <property name="geometry">
+     <rect>
+      <x>330</x>
+      <y>10</y>
+      <width>191</width>
+      <height>321</height>
+     </rect>
+    </property>
+    <property name="title">
+     <string>Feadback</string>
+    </property>
+    <widget class="QWidget" name="gridLayoutWidget">
+     <property name="geometry">
+      <rect>
+       <x>0</x>
+       <y>20</y>
+       <width>191</width>
+       <height>301</height>
+      </rect>
+     </property>
+     <layout class="QGridLayout" name="gridLayout_2">
+      <item row="2" column="0">
+       <widget class="QLabel" name="labelSetGearSt">
+        <property name="text">
+         <string> Setting Gear</string>
+        </property>
+       </widget>
+      </item>
+      <item row="6" column="0">
+       <widget class="QLabel" name="labelMacErr">
+        <property name="text">
+         <string>StateMachine</string>
+        </property>
+       </widget>
+      </item>
+      <item row="0" column="0">
+       <widget class="QLabel" name="labelHandSharkSt">
+        <property name="text">
+         <string>HandSake ST</string>
+        </property>
+       </widget>
+      </item>
+      <item row="5" column="0">
+       <widget class="QLabel" name="labelChaissErr">
+        <property name="text">
+         <string>  Chassis Err</string>
+        </property>
+       </widget>
+      </item>
+      <item row="3" column="0">
+       <widget class="QLabel" name="labelSpeed">
+        <property name="text">
+         <string>     Speed</string>
+        </property>
+       </widget>
+      </item>
+      <item row="1" column="0">
+       <widget class="QLabel" name="labelCurGearSt">
+        <property name="text">
+         <string> Current Gear</string>
+        </property>
+       </widget>
+      </item>
+      <item row="4" column="0">
+       <widget class="QLabel" name="labelEPS">
+        <property name="text">
+         <string>       EPS</string>
+        </property>
+       </widget>
+      </item>
+      <item row="0" column="1">
+       <widget class="QLineEdit" name="lineEHandSake">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item row="1" column="1">
+       <widget class="QLineEdit" name="lineECurGear">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item row="2" column="1">
+       <widget class="QLineEdit" name="lineESetGear">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item row="4" column="1">
+       <widget class="QLineEdit" name="lineEEPS">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item row="3" column="1">
+       <widget class="QLineEdit" name="lineESpeed">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item row="5" column="1">
+       <widget class="QLineEdit" name="lineEChaissErr">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item row="6" column="1">
+       <widget class="QLineEdit" name="lineEMachErr">
+        <property name="readOnly">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+     </layout>
+    </widget>
+   </widget>
+   <widget class="QGroupBox" name="groupBox_2">
+    <property name="geometry">
+     <rect>
+      <x>0</x>
+      <y>0</y>
+      <width>331</width>
+      <height>331</height>
+     </rect>
+    </property>
+    <property name="title">
+     <string>Control CMD</string>
+    </property>
+    <widget class="QCheckBox" name="cBox_Handshake">
+     <property name="geometry">
+      <rect>
+       <x>10</x>
+       <y>30</y>
+       <width>101</width>
+       <height>23</height>
+      </rect>
+     </property>
+     <property name="text">
+      <string>Handshake</string>
+     </property>
+    </widget>
+    <widget class="QGroupBox" name="groupBox_3">
+     <property name="geometry">
+      <rect>
+       <x>10</x>
+       <y>60</y>
+       <width>101</width>
+       <height>111</height>
+      </rect>
+     </property>
+     <property name="title">
+      <string>Gear Ctrl</string>
+     </property>
+     <widget class="QWidget" name="verticalLayoutWidget">
+      <property name="geometry">
+       <rect>
+        <x>0</x>
+        <y>20</y>
+        <width>101</width>
+        <height>91</height>
+       </rect>
+      </property>
+      <layout class="QVBoxLayout" name="verticalLayout">
+       <item>
+        <widget class="QCheckBox" name="cBoxGearD">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>D</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QCheckBox" name="cBoxGearR">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>R</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QCheckBox" name="cBoxGearP">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>P</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </widget>
+    </widget>
+    <widget class="QGroupBox" name="groupBox_4">
+     <property name="geometry">
+      <rect>
+       <x>10</x>
+       <y>190</y>
+       <width>101</width>
+       <height>111</height>
+      </rect>
+     </property>
+     <property name="title">
+      <string>Cornering lamp</string>
+     </property>
+     <widget class="QWidget" name="verticalLayoutWidget_2">
+      <property name="geometry">
+       <rect>
+        <x>0</x>
+        <y>20</y>
+        <width>101</width>
+        <height>89</height>
+       </rect>
+      </property>
+      <layout class="QVBoxLayout" name="verticalLayout_2">
+       <item>
+        <widget class="QCheckBox" name="cBoxLampL">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>Turn Left</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QCheckBox" name="cBoxLampR">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>Turn Right</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QCheckBox" name="cBoxLampH">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>Off</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </widget>
+    </widget>
+    <widget class="QGroupBox" name="groupBox_5">
+     <property name="geometry">
+      <rect>
+       <x>130</x>
+       <y>40</y>
+       <width>81</width>
+       <height>281</height>
+      </rect>
+     </property>
+     <property name="title">
+      <string>Speed Ctrl</string>
+     </property>
+     <widget class="QDoubleSpinBox" name="sBoxSpeedSet">
+      <property name="enabled">
+       <bool>false</bool>
+      </property>
+      <property name="geometry">
+       <rect>
+        <x>10</x>
+        <y>240</y>
+        <width>69</width>
+        <height>26</height>
+       </rect>
+      </property>
+      <property name="decimals">
+       <number>1</number>
+      </property>
+      <property name="maximum">
+       <double>30.000000000000000</double>
+      </property>
+     </widget>
+     <widget class="QSlider" name="vSliderSpeedSet">
+      <property name="enabled">
+       <bool>false</bool>
+      </property>
+      <property name="geometry">
+       <rect>
+        <x>30</x>
+        <y>30</y>
+        <width>16</width>
+        <height>201</height>
+       </rect>
+      </property>
+      <property name="maximum">
+       <number>30</number>
+      </property>
+      <property name="pageStep">
+       <number>2</number>
+      </property>
+      <property name="orientation">
+       <enum>Qt::Vertical</enum>
+      </property>
+     </widget>
+    </widget>
+    <widget class="QGroupBox" name="groupBox_6">
+     <property name="geometry">
+      <rect>
+       <x>230</x>
+       <y>40</y>
+       <width>81</width>
+       <height>281</height>
+      </rect>
+     </property>
+     <property name="title">
+      <string>EPS Ctrl</string>
+     </property>
+     <widget class="QSlider" name="vSliderEpsSet">
+      <property name="enabled">
+       <bool>false</bool>
+      </property>
+      <property name="geometry">
+       <rect>
+        <x>30</x>
+        <y>30</y>
+        <width>16</width>
+        <height>201</height>
+       </rect>
+      </property>
+      <property name="minimum">
+       <number>-400</number>
+      </property>
+      <property name="maximum">
+       <number>400</number>
+      </property>
+      <property name="orientation">
+       <enum>Qt::Vertical</enum>
+      </property>
+     </widget>
+     <widget class="QDoubleSpinBox" name="sBoxEpsSet">
+      <property name="enabled">
+       <bool>false</bool>
+      </property>
+      <property name="geometry">
+       <rect>
+        <x>10</x>
+        <y>240</y>
+        <width>69</width>
+        <height>26</height>
+       </rect>
+      </property>
+      <property name="decimals">
+       <number>1</number>
+      </property>
+      <property name="minimum">
+       <double>-400.000000000000000</double>
+      </property>
+      <property name="maximum">
+       <double>400.000000000000000</double>
+      </property>
+      <property name="singleStep">
+       <double>10.000000000000000</double>
+      </property>
+     </widget>
+    </widget>
+   </widget>
+  </widget>
+  <widget class="QToolBar" name="mainToolBar">
+   <attribute name="toolBarArea">
+    <enum>TopToolBarArea</enum>
+   </attribute>
+   <attribute name="toolBarBreak">
+    <bool>false</bool>
+   </attribute>
+  </widget>
+  <widget class="QStatusBar" name="statusBar"/>
+ </widget>
+ <layoutdefault spacing="6" margin="11"/>
+ <resources/>
+ <connections/>
+</ui>