Browse Source

add controller

jinliang 3 years ago
parent
commit
5ffabca934

+ 51 - 0
src/controller/controller_rubshCar/boost.h

@@ -0,0 +1,51 @@
+#pragma once
+
+#ifndef _IV_BOOST_H_
+#define _IV_BOOST_H_
+
+#if defined __GNUC__
+#  pragma GCC system_header 
+#endif
+#ifndef __CUDACC__
+//https://bugreports.qt-project.org/browse/QTBUG-22829
+#ifndef Q_MOC_RUN
+#include <boost/version.hpp>
+#include <boost/numeric/conversion/cast.hpp>
+#include <boost/thread/mutex.hpp>
+#include <boost/thread/condition.hpp>
+#include <boost/thread.hpp>
+#include <boost/thread/thread.hpp>
+#include <boost/filesystem.hpp>
+#include <boost/bind.hpp>
+#include <boost/cstdint.hpp>
+#include <boost/function.hpp>
+#include <boost/tuple/tuple.hpp>
+#include <boost/shared_ptr.hpp>
+#include <boost/weak_ptr.hpp>
+#include <boost/mpl/fold.hpp>
+#include <boost/mpl/inherit.hpp>
+#include <boost/mpl/inherit_linearly.hpp>
+#include <boost/mpl/joint_view.hpp>
+#include <boost/mpl/transform.hpp>
+#include <boost/mpl/vector.hpp>
+#include <boost/algorithm/string.hpp>
+#ifndef Q_MOC_RUN
+#include <boost/date_time/posix_time/posix_time.hpp>
+#endif
+#if BOOST_VERSION >= 104700
+#include <boost/chrono.hpp>
+#endif
+#include <boost/tokenizer.hpp>
+#include <boost/foreach.hpp>
+#include <boost/shared_array.hpp>
+#include <boost/interprocess/sync/file_lock.hpp>
+#if BOOST_VERSION >= 104900
+#include <boost/interprocess/permissions.hpp>
+#endif
+#include <boost/iostreams/device/mapped_file.hpp>
+#define BOOST_PARAMETER_MAX_ARITY 7
+#include <boost/signals2.hpp>
+#include <boost/signals2/slot.hpp>
+#endif
+#endif
+#endif    // _IV_BOOST_H_

+ 10 - 0
src/controller/controller_rubshCar/control/control.pri

@@ -0,0 +1,10 @@
+HEADERS += \
+    $$PWD/controller.h \
+    $$PWD/control_status.h \
+    $$PWD/vv7.h
+
+SOURCES += \
+    $$PWD/controller.cpp \
+    $$PWD/control_status.cpp
+
+DISTFILES +=

+ 89 - 0
src/controller/controller_rubshCar/control/control_status.cpp

@@ -0,0 +1,89 @@
+#include <control/control_status.h>
+#include <QDebug>
+//#if 1
+
+void iv::control::ControlStatus::set_wheel_angle(float angle)
+{
+
+    int ang =(angle+870)*10;
+    ServiceControlStatus.cmd_steer.bit.steering_pos_req_H = (ang)  /256;
+    ServiceControlStatus.cmd_steer.bit.steering_pos_req_L = (ang)  % 256;
+}
+
+void iv::control::ControlStatus::set_wheel_speed(float speed)
+{
+
+    int angSpeed =speed;
+    ServiceControlStatus.cmd_steer.bit.steering_val_req = angSpeed;
+}
+
+void iv::control::ControlStatus::set_wheel_enable(bool enable)
+{
+
+    if(enable){
+        ServiceControlStatus.cmd_steer.bit.steering_enb = 1;
+    }else{
+        ServiceControlStatus.cmd_steer.bit.steering_enb = 0;
+    }
+}
+
+void iv::control::ControlStatus::set_torque(float troque)
+{
+    ServiceControlStatus.cmd_drive.bit.driver_tq_reqH=(unsigned)((int)troque*100/256);
+    ServiceControlStatus.cmd_drive.bit.driver_tq_reqL=(unsigned)((int)troque*100%256);
+}
+
+void iv::control::ControlStatus::set_brake(float brake)
+{
+    ServiceControlStatus.cmd_brake.bit.brake_tq_reqH=(unsigned)((int)brake*100/255);
+    ServiceControlStatus.cmd_brake.bit.brake_tq_reqL=(unsigned)((int)brake*100%255);
+}
+void iv::control::ControlStatus::set_brake_en(bool enable)
+{
+    if(enable)
+        ServiceControlStatus.cmd_brake.bit.brake_enb = 1;
+    else
+        ServiceControlStatus.cmd_brake.bit.brake_enb = 0;
+}
+
+void iv::control::ControlStatus::set_gear(int gear)
+{
+    cmd_gear.bit.gear_shift_req = (unsigned)gear;
+}
+
+void iv::control::ControlStatus::set_handBrake(bool handbrake)
+{
+    if(handbrake){
+        cmd_park.bit.park_cmd = 1;
+    }else{
+        cmd_park.bit.park_cmd = 0;
+    }
+}
+void iv::control::ControlStatus::set_handBrake_en(bool handbrake)
+{
+    if(handbrake){
+        cmd_park.bit.park_enb = 2;
+    }else{
+        cmd_park.bit.park_enb = 1;
+    }
+}
+
+void iv::control::ControlStatus::set_gear_enable(bool enable){
+    if (enable == true)
+        cmd_gear.bit.gear_enb = 1;
+    else
+        cmd_gear.bit.gear_enb = 0;
+}
+
+void iv::control::ControlStatus::set_acc_enable(bool enable){
+    if (enable == true)
+        cmd_drive.bit.drive_enb = 1;
+    else
+        cmd_drive.bit.drive_enb = 0;
+}
+
+
+
+
+
+

+ 70 - 0
src/controller/controller_rubshCar/control/control_status.h

@@ -0,0 +1,70 @@
+#pragma once
+//由于控制器指令共享同一个ID 0x20,建立此类维护控制指令的最新状态
+
+#include <boost.h>
+#include <cstdint>
+#include <boost/serialization/singleton.hpp>
+#include <control/vv7.h>
+
+namespace iv {
+namespace control {
+class ControlStatus : public boost::noncopyable
+{
+public:
+
+//    ControlStatus(){}
+    /*****************
+             * ****测试标志位*****
+             * ***************/
+    int normal_speed  = 0;//常规速度
+    int swerve_speed  = 0;//转弯速度
+    int high_speed = 0;//快速
+    int mid_speed = 0;//中速
+    int low_speed = 0;//慢速
+    int change_line  = -1;//换道标志
+    int stop_obstacle = -1;//停障标志
+    int elude_obstacle = -1;//避障标志
+    int special_signle = -1;//特殊信号标志
+    int car_pullover = -1;//靠边停车标志位
+    float torque = 0.0;
+    float brake = 0.0;
+    float acc=0.0;
+
+    Command_Response command_reponse;
+    Cmd_gear_shift cmd_gear;
+    Cmd_steer_control cmd_steer;
+    Cmd_drive_control cmd_drive;
+    Cmd_brake_ctrl cmd_brake;
+    Cmd_park cmd_park;
+
+    int cmd_id_gear = 0xA1;
+    int cmd_id_steer = 0xA2;
+    int cmd_id_drive = 0xA3;
+    int cmd_id_brake = 0xA4;
+    int cmd_id_park = 0xA5;
+    int cmd_id_fb_vcu = 0xC1;
+    int cmd_id_fb_bms = 0xC2;
+    int cmd_id_fb_model = 0xC3;
+
+    void set_wheel_angle(float angle);
+    void set_wheel_speed(float speed);
+    void set_wheel_enable(bool enable);
+
+    void set_speed_limit(float speed);
+    void set_torque(float percent);
+    void set_aeb(float aeb);
+    void set_brake(float brake);
+    void set_brake_en(bool enable);
+    void set_gear(int gear);
+    void set_handBrake(bool handBrake);
+    void set_handBrake_en(bool enable);
+    void set_driveMode(char mode);
+    void set_gear_enable(bool enable);
+    void set_aeb_enable(bool enable);
+    void set_acc_enable(bool enable);
+
+};
+typedef boost::serialization::singleton<iv::control::ControlStatus> ControlStatusSingleton;
+}
+}
+#define ServiceControlStatus iv::control::ControlStatusSingleton::get_mutable_instance()

+ 145 - 0
src/controller/controller_rubshCar/control/controlcan.h

@@ -0,0 +1,145 @@
+#ifndef CONTROLCAN1_H
+#define CONTROLCAN1_H
+
+
+#ifdef linux
+//接口卡类型定义
+#define VCI_PCI5121		1
+#define VCI_PCI9810		2
+#define VCI_USBCAN1		3
+#define VCI_USBCAN2		4
+#define VCI_PCI9820		5
+#define VCI_CAN232		6
+#define VCI_PCI5110		7
+#define VCI_CANLite		8
+#define VCI_ISA9620		9
+#define VCI_ISA5420		10
+
+//CAN错误码
+#define	ERR_CAN_OVERFLOW			0x0001	//CAN控制器内部FIFO溢出
+#define	ERR_CAN_ERRALARM			0x0002	//CAN控制器错误报警
+#define	ERR_CAN_PASSIVE				0x0004	//CAN控制器消极错误
+#define	ERR_CAN_LOSE				0x0008	//CAN控制器仲裁丢失
+#define	ERR_CAN_BUSERR				0x0010	//CAN控制器总线错误
+
+//通用错误码
+#define	ERR_DEVICEOPENED			0x0100	//设备已经打开
+#define	ERR_DEVICEOPEN				0x0200	//打开设备错误
+#define	ERR_DEVICENOTOPEN			0x0400	//设备没有打开
+#define	ERR_BUFFEROVERFLOW			0x0800	//缓冲区溢出
+#define	ERR_DEVICENOTEXIST			0x1000	//此设备不存在
+#define	ERR_LOADKERNELDLL			0x2000	//装载动态库失败
+#define ERR_CMDFAILED				0x4000	//执行命令失败错误码
+#define	ERR_BUFFERCREATE			0x8000	//内存不足
+
+
+//函数调用返回状态值
+#define	STATUS_OK					1
+#define STATUS_ERR					0
+	
+#define USHORT unsigned short int
+#define BYTE unsigned char
+#define CHAR char
+#define UCHAR unsigned char
+#define UINT unsigned int
+#define DWORD unsigned int
+#define PVOID void*
+#define ULONG unsigned int
+#define INT int
+#define UINT32 UINT
+#define LPVOID void*
+#define BOOL BYTE
+#define TRUE 1
+#define FALSE 0
+
+
+#if 1
+
+typedef  struct  _VCI_BOARD_INFO{//1.ZLGCAN系列接口卡信息的数据类型。
+		USHORT	hw_Version;
+		USHORT	fw_Version;
+		USHORT	dr_Version;
+		USHORT	in_Version;
+		USHORT	irq_Num;
+		BYTE	can_Num;
+		CHAR	str_Serial_Num[20];
+		CHAR	str_hw_Type[40];
+		USHORT	Reserved[4];
+} VCI_BOARD_INFO,*PVCI_BOARD_INFO; 
+
+
+typedef  struct  _VCI_CAN_OBJ{//2.定义CAN信息帧的数据类型。
+	UINT	ID;
+	UINT	TimeStamp;
+	BYTE	TimeFlag;
+	BYTE	SendType;
+	BYTE	RemoteFlag;//是否是远程帧
+	BYTE	ExternFlag;//是否是扩展帧
+	BYTE	DataLen;
+	BYTE	Data[8];
+	BYTE	Reserved[3];
+}VCI_CAN_OBJ,*PVCI_CAN_OBJ;
+
+
+typedef struct _VCI_CAN_STATUS{//3.定义CAN控制器状态的数据类型。
+	UCHAR	ErrInterrupt;
+	UCHAR	regMode;
+	UCHAR	regStatus;
+	UCHAR	regALCapture;
+	UCHAR	regECCapture; 
+	UCHAR	regEWLimit;
+	UCHAR	regRECounter; 
+	UCHAR	regTECounter;
+	DWORD	Reserved;
+}VCI_CAN_STATUS,*PVCI_CAN_STATUS;
+
+
+typedef struct _ERR_INFO{//4.定义错误信息的数据类型。
+		UINT	ErrCode;
+		BYTE	Passive_ErrData[3];
+		BYTE	ArLost_ErrData;
+} VCI_ERR_INFO,*PVCI_ERR_INFO;
+
+
+typedef struct _INIT_CONFIG{//5.定义初始化CAN的数据类型
+	DWORD	AccCode;
+	DWORD	AccMask;
+	DWORD	Reserved;
+	UCHAR	Filter;
+	UCHAR	Timing0;	
+	UCHAR	Timing1;	
+	UCHAR	Mode;
+}VCI_INIT_CONFIG,*PVCI_INIT_CONFIG;
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+DWORD VCI_OpenDevice(DWORD DeviceType,DWORD DeviceInd,DWORD Reserved);
+DWORD VCI_CloseDevice(DWORD DeviceType,DWORD DeviceInd);
+DWORD VCI_InitCAN(DWORD DeviceType, DWORD DeviceInd, DWORD CANInd, PVCI_INIT_CONFIG pInitConfig);
+
+DWORD VCI_ReadBoardInfo(DWORD DeviceType,DWORD DeviceInd,PVCI_BOARD_INFO pInfo);
+DWORD VCI_ReadErrInfo(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_ERR_INFO pErrInfo);
+DWORD VCI_ReadCANStatus(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_STATUS pCANStatus);
+
+DWORD VCI_GetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
+DWORD VCI_SetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
+
+ULONG VCI_GetReceiveNum(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+DWORD VCI_ClearBuffer(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+
+DWORD VCI_StartCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+DWORD VCI_ResetCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+
+ULONG VCI_Transmit(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pSend,UINT Len);
+ULONG VCI_Receive(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pReceive,UINT Len,INT WaitTime);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif
+
+#endif

+ 74 - 0
src/controller/controller_rubshCar/control/controller.cpp

@@ -0,0 +1,74 @@
+#include <control/controller.h>
+
+iv::control::Controller::Controller() {
+
+}
+
+iv::control::Controller::~Controller() {
+
+}
+
+void iv::control::Controller::inialize() {
+
+}
+////校验和
+//void iv::control::Controller::cmd_checksum(unsigned char cmd_id) {
+//    ServiceControlStatus.set_cmd_checksum(cmd_id);
+//}
+//方向盘控制
+void iv::control::Controller::control_wheel(float angle) {
+    ServiceControlStatus.set_wheel_angle(angle);
+}
+
+void iv::control::Controller:: control_angle_speed(float angSpeed){
+    ServiceControlStatus.set_wheel_speed(angSpeed);
+}
+
+void iv::control::Controller:: control_angle_enable(bool enable){
+    ServiceControlStatus.set_wheel_enable(enable);
+}
+//速度限制
+//void iv::control::Controller:: control_speed_limit(float speedLimit){
+//    ServiceControlStatus.set_speed_limit(speedLimit);
+//}
+//油门控制
+void iv::control::Controller::control_torque(float percent){
+    ServiceControlStatus.set_torque(percent);
+}
+void iv::control::Controller::control_acc_en(bool enanble){
+    ServiceControlStatus.set_acc_enable(enanble);
+}
+
+//void iv::control::Controller::control_aeb(float aeb){
+//    ServiceControlStatus.set_aeb(aeb);
+//}
+//void iv::control::Controller::control_aeb_en(bool enable){
+//    ServiceControlStatus.set_aeb_enable(enable);
+//}
+//刹车控制
+void iv::control::Controller::control_brake_en(bool enable){
+    ServiceControlStatus.set_brake_en(enable);
+}
+//刹车控制
+void iv::control::Controller::control_brake(float brake){
+    ServiceControlStatus.set_brake(brake);
+}
+//档位控制
+void iv::control::Controller::control_gear(float gear){
+    ServiceControlStatus.set_gear(gear);
+}
+void iv::control::Controller::control_gear_en(bool enable){
+    ServiceControlStatus.set_gear_enable(enable);
+}
+//手刹
+void iv::control::Controller::control_handBrake(bool  enable){
+    ServiceControlStatus.set_handBrake(enable);
+}
+//手刹
+void iv::control::Controller::control_handBrake_en(bool  enable){
+    ServiceControlStatus.set_handBrake_en(enable);
+}
+
+
+
+

+ 47 - 0
src/controller/controller_rubshCar/control/controller.h

@@ -0,0 +1,47 @@
+#pragma once
+/*
+*控制器
+*/
+#ifndef _IV_CONTROL_CONTROLLER_
+#define _IV_CONTROL_CONTROLLER_
+
+#include <boost.h>
+//#include <common/car_status.h>
+#include <control/control_status.h>
+
+namespace iv {
+    namespace control {
+        class Controller
+        {
+        public:
+            Controller();
+            ~Controller();
+            void inialize();// 初始化
+
+
+            void control_wheel(float angle);		//方向盘控制
+            void control_angle_speed(float angSpeed);
+            void control_angle_enable(bool enable);
+
+            void control_speed_limit(float speedLimit);
+            void control_torque(float percent);	//油门开度控制
+            void control_aeb(float aeb);	//油门开度控制
+            void control_brake_en(bool enable);
+            void control_brake(float brake);
+            void control_gear(float gear);
+            void control_handBrake(bool  enable);
+            void control_handBrake_en(bool  enable);
+            void control_mode(char mode);
+            void control_gear_en(bool enable);
+            void control_aeb_en(bool enable);
+            void control_acc_en(bool enanble);
+
+            ///* 获取当前车辆状态*/
+            //void getCurrentCarStatus(iv::CarStatus & car_status);
+
+        private:
+        };
+    }
+}
+
+#endif // !_IV_CONTROL_CONTROLLER_

+ 125 - 0
src/controller/controller_rubshCar/control/vv7.h

@@ -0,0 +1,125 @@
+#pragma once
+
+struct cmd_gear_shift_bit8
+{
+    unsigned char gear_enb;
+    unsigned char gear_shift_req;
+//    unsigned char reserved2 = 0;
+//    unsigned char reserved3 = 0;
+//    unsigned char reserved4 = 0;
+//    unsigned char reserved5 = 0;
+//    unsigned char reserved6 = 0;
+//    unsigned char reserved7 = 0;
+    unsigned char reserved2 ;
+    unsigned char reserved3;
+    unsigned char reserved4 ;
+    unsigned char reserved5 ;
+    unsigned char reserved6;
+    unsigned char reserved7;
+};
+
+union Cmd_gear_shift
+{
+    cmd_gear_shift_bit8 bit;
+    unsigned char byte[8];
+};
+
+struct  cmd_steer_control_bit
+{
+    unsigned char steering_enb;
+    unsigned char steering_pos_req_L;
+    unsigned char steering_pos_req_H;
+    unsigned char steering_val_req;
+    unsigned char reserved4 ;
+    unsigned char reserved5;
+    unsigned char reserved6 ;
+    unsigned char reserved7;
+};
+
+union Cmd_steer_control
+{
+    cmd_steer_control_bit bit;
+    unsigned char byte[8];
+};
+
+struct  cmd_drive_control_bit
+{
+    unsigned char drive_enb;
+    unsigned char drive_tq_req ;
+    unsigned char driver_tq_reqL;
+    unsigned char driver_tq_reqH;
+    unsigned char reserved4 ;
+    unsigned char reserved5 ;
+    unsigned char reserved6 ;
+    unsigned char reserved7 ;
+};
+
+union Cmd_drive_control
+{
+    cmd_drive_control_bit bit;
+    unsigned char byte[8];
+};
+
+struct cmd_brake_ctrl_bit
+{
+    unsigned char brake_enb;
+    unsigned char brake_tq_reqL;
+    unsigned char brake_tq_reqH;
+    unsigned char reserved3 ;
+    unsigned char reserved4 ;
+    unsigned char reserved5 ;
+    unsigned char reserved6 ;
+    unsigned char reserved7 ;
+};
+
+union Cmd_brake_ctrl
+{
+    cmd_brake_ctrl_bit bit;
+    unsigned char byte[8];
+};
+
+struct cmd_park_bit
+{
+    unsigned char park_enb;
+    unsigned char park_cmd;
+    unsigned char reserved2 ;
+    unsigned char reserved3 ;
+    unsigned char reserved4 ;
+    unsigned char reserved5 ;
+    unsigned char reserved6 ;
+    unsigned char reserved7 ;
+};
+union Cmd_park
+{
+    cmd_park_bit bit;
+    unsigned char byte[8];
+};
+
+struct Command_Response_Bit
+{
+    unsigned char head;
+
+
+    unsigned char grade : 2;
+    unsigned char driveMode : 2;
+    unsigned char epb : 1;
+    unsigned char epsMode : 2;
+    unsigned char  obligate: 1;
+
+
+};
+
+union Command_Response
+{
+    Command_Response_Bit bit;
+
+    unsigned char byte[2];
+};
+
+
+
+
+
+
+
+

+ 65 - 0
src/controller/controller_rubshCar/controller_rubshCar.pro

@@ -0,0 +1,65 @@
+QT -= gui
+
+QT += network xml dbus
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which as been marked 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 += $$PWD/main.cpp \
+    ../../include/msgtype/cameraobject.pb.cc \
+    ../../include/msgtype/cameraobjectarray.pb.cc \
+    ../../include/msgtype/decition.pb.cc \
+    ../../include/msgtype/brainstate.pb.cc \
+    ../../include/msgtype/canmsg.pb.cc \
+    ../../include/msgtype/canraw.pb.cc \
+    ../../include/msgtype/chassis.pb.cc
+
+include($$PWD/control/control.pri)
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+!include(../../../include/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}
+
+!include(../../../include/ivboost.pri ) {
+    error( "Couldn't find the ivboost.pri file!" )
+}
+
+!include(../controllercommon/controllercommon.pri ) {
+    error( "Couldn't find the controllercommon.pri.pri file!" )
+}
+
+INCLUDEPATH += $$PWD/../controllercommon
+
+
+DEFINES += TORQUEBRAKETEST
+
+#unix:!macx: LIBS += -L/home/yuchuli/qt/lib -lncomgnss -ladcmemshare
+
+unix:!macx: INCLUDEPATH += $$PWD/.
+unix:!macx: DEPENDPATH += $$PWD/.
+
+HEADERS += \
+    ../../include/msgtype/cameraobject.pb.h \
+    ../../include/msgtype/cameraobjectarray.pb.h \
+    ../../include/msgtype/decition.pb.h \
+    ../../include/msgtype/canmsg.pb.h \
+    ../../include/msgtype/canraw.pb.h \
+    ../../include/msgtype/chassis.pb.h
+
+

+ 322 - 0
src/controller/controller_rubshCar/main.cpp

@@ -0,0 +1,322 @@
+#include <QCoreApplication>
+
+#include <QTime>
+
+#include <QMutex>
+
+#include "control/control_status.h"
+#include "control/controller.h"
+
+#include "xmlparam.h"
+#include "modulecomm.h"
+#include "ivbacktrace.h"
+#include "ivversion.h"
+
+#include "canmsg.pb.h"
+#include "decition.pb.h"
+#include "chassis.pb.h"
+
+#include "torquebrake.h"
+
+#include <thread>
+
+void * gpacansend;
+void * gpadecition;
+void * gpachassis;
+
+std::string gstrmemdecition;
+std::string gstrmemcansend;
+std::string gstrmemchassis;
+bool gbSendRun = true;
+
+bool gbChassisEPS = false;
+
+iv::brain::decition gdecition_def;
+iv::brain::decition gdecition;
+
+QTime gTime;
+int gnLastSendTime = 0;
+int gnLastRecvDecTime = -1000;
+int gnDecitionNum = 0; //when is zero,send default;
+const int gnDecitionNumMax = 100;
+int gnIndex = 0;
+
+boost::shared_ptr<iv::control::Controller> gcontroller;	//实际车辆控制器
+
+bool bHasGearCmd = false;
+bool bHasSteerCmd = false;
+bool bHasDriveCmd = false;
+bool bHasBrakeCmd = false;
+bool bHasParkCmd = false;
+
+static QMutex gMutex;
+
+void executeDecition(const iv::brain::decition decition)
+{
+    if(decition.has_gear())
+    {
+        gcontroller->control_gear_en(true);
+        gcontroller->control_gear(decition.gear());
+        bHasGearCmd = true;
+    }
+    if(decition.has_wheelangle())
+    {
+        gcontroller->control_angle_enable(true);
+        gcontroller->control_wheel(decition.wheelangle());
+        gcontroller->control_angle_speed(decition.wheelspeed());
+        bHasSteerCmd = true;
+    }
+
+    if(decition.has_accelerator())
+    {
+        gcontroller->control_acc_en(true);
+        gcontroller->control_torque(decition.torque());
+        bHasDriveCmd = true;
+    }
+    if(decition.has_brake())
+    {
+        gcontroller->control_brake_en(true);
+        gcontroller->control_brake(decition.brake());
+        bHasBrakeCmd = true;
+    }
+    if(decition.has_handbrake())
+    {
+        gcontroller->control_handBrake_en(true);
+        gcontroller->control_handBrake(decition.handbrake());
+        bHasParkCmd = true;
+    }
+
+
+#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());
+        }
+        gnothavetb++;
+    }
+
+#endif
+
+}
+
+void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
+{
+    iv::chassis xchassis;
+    static int ncount = 0;
+    if(!xchassis.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"iv::decition::BrainDecition::UpdateChassis ParseFrom Array Error."<<std::endl;
+        return;
+    }
+
+    if(xchassis.epsmode() == 0)
+    {
+        gbChassisEPS = true;
+    }
+
+
+}
+
+
+void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    qint64 oldtime;
+    iv::brain::decition xdecition;
+
+    if(!xdecition.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"ListenDecition parse error."<<std::endl;
+        return;
+    }
+
+    if(xdecition.gear() != 4)
+    {
+        qDebug("not D");
+    }
+    if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %ld diff is %ld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
+    oldtime = QDateTime::currentMSecsSinceEpoch();
+    gMutex.lock();
+    gdecition.CopyFrom(xdecition);
+    gMutex.unlock();
+    gnDecitionNum = gnDecitionNumMax;
+    gbChassisEPS = false;
+
+}
+
+void ExecSend()
+{
+    iv::can::canmsg xmsg;
+    iv::can::canraw xraw;
+    if(bHasGearCmd)
+    {
+        xraw.set_id(ServiceControlStatus.cmd_id_gear);
+        xraw.set_data(ServiceControlStatus.cmd_gear.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);
+        bHasGearCmd = false;
+    }
+    if(bHasSteerCmd)
+    {
+        xraw.set_id(ServiceControlStatus.cmd_id_steer);
+        xraw.set_data(ServiceControlStatus.cmd_steer.byte,8);
+        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);
+        bHasSteerCmd = false;
+    }
+
+    if(bHasDriveCmd)
+    {
+        xraw.set_id(ServiceControlStatus.cmd_id_drive);
+        xraw.set_data(ServiceControlStatus.cmd_drive.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);
+        bHasDriveCmd = false;
+    }
+    if(bHasBrakeCmd)
+    {
+        xraw.set_id(ServiceControlStatus.cmd_id_brake);
+        xraw.set_data(ServiceControlStatus.cmd_brake.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);
+        bHasBrakeCmd = false;
+    }
+    if(bHasParkCmd)
+    {
+        xraw.set_id(ServiceControlStatus.cmd_id_park);
+        xraw.set_data(ServiceControlStatus.cmd_park.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);
+        bHasParkCmd = false;
+    }
+
+    gnIndex++;
+    xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
+    int ndatasize = xmsg.ByteSize();
+    char * strser = new char[ndatasize];
+    std::shared_ptr<char> pstrser;
+    pstrser.reset(strser);
+    if(xmsg.SerializeToArray(strser,ndatasize))
+    {
+        iv::modulecomm::ModuleSendMsg(gpacansend,strser,ndatasize);
+    }
+    else
+    {
+        std::cout<<"MainWindow::onTimer serialize error."<<std::endl;
+    }
+}
+
+//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;
+//}
+
+void sendthread()
+{
+//    initial();
+    iv::brain::decition xdecition;
+    while(gbSendRun)
+    {
+        if(gnDecitionNum <= 0)
+        {
+            xdecition.CopyFrom(gdecition_def);
+        }
+        else
+        {
+            gMutex.lock();
+            xdecition.CopyFrom(gdecition);
+            gMutex.unlock();
+            gnDecitionNum--;
+        }
+        executeDecition(xdecition);
+        if(gbChassisEPS == false) ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+}
+
+int main(int argc, char *argv[])
+{
+    RegisterIVBackTrace();
+    showversion("controller_hapo");
+    QCoreApplication a(argc, argv);
+
+    QString strpath = QCoreApplication::applicationDirPath();
+
+    if(argc < 2)
+        strpath = strpath + "/controller_vv7.xml";
+    else
+        strpath = argv[1];
+    std::cout<<strpath.toStdString()<<std::endl;
+
+    gdecition_def.set_accelerator(-0.5);
+    //    gdecition_def.set_brake(1.0);
+    gdecition_def.set_brake(20);   //apollo_fu 20200417
+    gdecition_def.set_torque(0);
+    // gdecition_def.set_rightlamp(true);
+    //  gdecition_def.set_doublespark(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);
+    gTime.start();
+
+    gcontroller = boost::shared_ptr<iv::control::Controller>(new iv::control::Controller());
+
+    iv::xmlparam::Xmlparam xp(strpath.toStdString());
+
+    gstrmemcansend = xp.GetParam("cansend","cansend0");
+    gstrmemdecition = xp.GetParam("dection","deciton");
+    gstrmemchassis = xp.GetParam("chassismsgname","chassis");
+
+    gpacansend = iv::modulecomm::RegisterSend(gstrmemcansend.data(),10000,1);
+    gpadecition = iv::modulecomm::RegisterRecv(gstrmemdecition.data(),ListenDeciton);
+    gpachassis = iv::modulecomm::RegisterRecv(gstrmemchassis.data(),UpdateChassis);
+
+#ifdef TORQUEBRAKETEST
+    EnableTorqueBrakeTest();
+#endif
+
+    std::thread xthread(sendthread);
+
+    return a.exec();
+}