瀏覽代碼

changan shenlan V2 cocntroller

chenxiaowei 2 年之前
父節點
當前提交
e55d3db56e

+ 1464 - 0
src/controller/controller_changan_shenlan_v2/BCAN_dbc.c

@@ -0,0 +1,1464 @@
+/* Generated by DBCC, see <https://github.com/howerj/dbcc> */
+#include "BCAN_dbc.h"
+#include <inttypes.h>
+#include <assert.h>
+
+#define UNUSED(X) ((void)(X))
+
+static inline uint64_t reverse_byte_order(uint64_t x) {
+	x = (x & 0x00000000FFFFFFFF) << 32 | (x & 0xFFFFFFFF00000000) >> 32;
+	x = (x & 0x0000FFFF0000FFFF) << 16 | (x & 0xFFFF0000FFFF0000) >> 16;
+	x = (x & 0x00FF00FF00FF00FF) << 8  | (x & 0xFF00FF00FF00FF00) >> 8;
+	return x;
+}
+
+static inline int print_helper(int r, int print_return_value) {
+	return ((r >= 0) && (print_return_value >= 0)) ? r + print_return_value : -1;
+}
+
+static int pack_can_0x144_ECU_144(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* ACC_LatAngReq: start-bit 4, length 14, endianess motorola, scaling 0.1, offset -720 */
+	x = ((uint16_t)(o->can_0x144_ECU_144.ACC_LatAngReq)) & 0x3fff;
+	x <<= 47; 
+	m |= x;
+	/* ACC_MotorTorqueMaxLimitRequest: start-bit 21, length 11, endianess motorola, scaling 0.02, offset -20.48 */
+	x = ((uint16_t)(o->can_0x144_ECU_144.ACC_MotorTorqueMaxLimitRequest)) & 0x7ff;
+	x <<= 35; 
+	m |= x;
+	/* ACC_MotorTorqueMinLimitRequest: start-bit 26, length 11, endianess motorola, scaling 0.02, offset -20.48 */
+	x = ((uint16_t)(o->can_0x144_ECU_144.ACC_MotorTorqueMinLimitRequest)) & 0x7ff;
+	x <<= 24; 
+	m |= x;
+	/* ADS_Reqmode: start-bit 7, length 3, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x144_ECU_144.ADS_Reqmode)) & 0x7;
+	x <<= 61; 
+	m |= x;
+	/* ACC_ADCReqType: start-bit 47, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x144_ECU_144.ACC_ADCReqType)) & 0x3;
+	x <<= 22; 
+	m |= x;
+	/* ACC_LatAngReqActive: start-bit 22, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x144_ECU_144.ACC_LatAngReqActive)) & 0x1;
+	x <<= 46; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x144_ECU_144_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x144_ECU_144(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* ACC_LatAngReq: start-bit 4, length 14, endianess motorola, scaling 0.1, offset -720 */
+	x = (m >> 47) & 0x3fff;
+	o->can_0x144_ECU_144.ACC_LatAngReq = x;
+	/* ACC_MotorTorqueMaxLimitRequest: start-bit 21, length 11, endianess motorola, scaling 0.02, offset -20.48 */
+	x = (m >> 35) & 0x7ff;
+	o->can_0x144_ECU_144.ACC_MotorTorqueMaxLimitRequest = x;
+	/* ACC_MotorTorqueMinLimitRequest: start-bit 26, length 11, endianess motorola, scaling 0.02, offset -20.48 */
+	x = (m >> 24) & 0x7ff;
+	o->can_0x144_ECU_144.ACC_MotorTorqueMinLimitRequest = x;
+	/* ADS_Reqmode: start-bit 7, length 3, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 61) & 0x7;
+	o->can_0x144_ECU_144.ADS_Reqmode = x;
+	/* ACC_ADCReqType: start-bit 47, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 22) & 0x3;
+	o->can_0x144_ECU_144.ACC_ADCReqType = x;
+	/* ACC_LatAngReqActive: start-bit 22, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 46) & 0x1;
+	o->can_0x144_ECU_144.ACC_LatAngReqActive = x;
+	o->can_0x144_ECU_144_rx = 1;
+	o->can_0x144_ECU_144_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x144_ACC_LatAngReq(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x144_ECU_144.ACC_LatAngReq);
+	rval *= 0.1;
+	rval += -720;
+	if (rval <= 720) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x144_ACC_LatAngReq(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x144_ECU_144.ACC_LatAngReq = 0;
+	if (in > 720)
+		return -1;
+	in += 720;
+	in *= 10;
+	o->can_0x144_ECU_144.ACC_LatAngReq = in;
+	return 0;
+}
+
+int decode_can_0x144_ACC_MotorTorqueMaxLimitRequest(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x144_ECU_144.ACC_MotorTorqueMaxLimitRequest);
+	rval *= 0.02;
+	rval += -20.48;
+	if (rval <= 20.44) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x144_ACC_MotorTorqueMaxLimitRequest(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x144_ECU_144.ACC_MotorTorqueMaxLimitRequest = 0;
+	if (in > 20.44)
+		return -1;
+	in += 20.48;
+	in *= 50;
+	o->can_0x144_ECU_144.ACC_MotorTorqueMaxLimitRequest = in;
+	return 0;
+}
+
+int decode_can_0x144_ACC_MotorTorqueMinLimitRequest(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x144_ECU_144.ACC_MotorTorqueMinLimitRequest);
+	rval *= 0.02;
+	rval += -20.48;
+	if (rval <= 20.44) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x144_ACC_MotorTorqueMinLimitRequest(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x144_ECU_144.ACC_MotorTorqueMinLimitRequest = 0;
+	if (in > 20.44)
+		return -1;
+	in += 20.48;
+	in *= 50;
+	o->can_0x144_ECU_144.ACC_MotorTorqueMinLimitRequest = in;
+	return 0;
+}
+
+int decode_can_0x144_ADS_Reqmode(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x144_ECU_144.ADS_Reqmode);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x144_ADS_Reqmode(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x144_ECU_144.ADS_Reqmode = in;
+	return 0;
+}
+
+int decode_can_0x144_ACC_ADCReqType(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x144_ECU_144.ACC_ADCReqType);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x144_ACC_ADCReqType(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x144_ECU_144.ACC_ADCReqType = in;
+	return 0;
+}
+
+int decode_can_0x144_ACC_LatAngReqActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x144_ECU_144.ACC_LatAngReqActive);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x144_ACC_LatAngReqActive(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x144_ECU_144.ACC_LatAngReqActive = in;
+	return 0;
+}
+
+int print_can_0x144_ECU_144(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "ACC_LatAngReq = (wire: %.0f)\n", (double)(o->can_0x144_ECU_144.ACC_LatAngReq)));
+	r = print_helper(r, fprintf(output, "ACC_MotorTorqueMaxLimitRequest = (wire: %.0f)\n", (double)(o->can_0x144_ECU_144.ACC_MotorTorqueMaxLimitRequest)));
+	r = print_helper(r, fprintf(output, "ACC_MotorTorqueMinLimitRequest = (wire: %.0f)\n", (double)(o->can_0x144_ECU_144.ACC_MotorTorqueMinLimitRequest)));
+	r = print_helper(r, fprintf(output, "ADS_Reqmode = (wire: %.0f)\n", (double)(o->can_0x144_ECU_144.ADS_Reqmode)));
+	r = print_helper(r, fprintf(output, "ACC_ADCReqType = (wire: %.0f)\n", (double)(o->can_0x144_ECU_144.ACC_ADCReqType)));
+	r = print_helper(r, fprintf(output, "ACC_LatAngReqActive = (wire: %.0f)\n", (double)(o->can_0x144_ECU_144.ACC_LatAngReqActive)));
+	return r;
+}
+
+static int pack_can_0x147_ADC_147(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* EpsSasSteerAg: start-bit 9, length 16, endianess motorola, scaling 0.1, offset 0 */
+	x = ((uint16_t)(o->can_0x147_ADC_147.EpsSasSteerAg)) & 0xffff;
+	x <<= 34; 
+	m |= x;
+	/* EPS_Pinionang: start-bit 7, length 14, endianess motorola, scaling 0.1, offset -720 */
+	x = ((uint16_t)(o->can_0x147_ADC_147.EPS_Pinionang)) & 0x3fff;
+	x <<= 50; 
+	m |= x;
+	/* EspVehSpd: start-bit 41, length 13, endianess motorola, scaling 0.05625, offset 0 */
+	x = ((uint16_t)(o->can_0x147_ADC_147.EspVehSpd)) & 0x1fff;
+	x <<= 5; 
+	m |= x;
+	/* EpsSteerAgRate: start-bit 24, length 8, endianess motorola, scaling 4, offset 0 */
+	x = ((uint8_t)(o->can_0x147_ADC_147.EpsSteerAgRate)) & 0xff;
+	x <<= 25; 
+	m |= x;
+	/* EPS_ADS_Abortfeedback: start-bit 45, length 4, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x147_ADC_147.EPS_ADS_Abortfeedback)) & 0xf;
+	x <<= 18; 
+	m |= x;
+	/* EPS_LatCtrlAvailabilityStatus: start-bit 47, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x147_ADC_147.EPS_LatCtrlAvailabilityStatus)) & 0x3;
+	x <<= 22; 
+	m |= x;
+	/* EpsSasSteerAgVld: start-bit 25, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x147_ADC_147.EpsSasSteerAgVld)) & 0x1;
+	x <<= 33; 
+	m |= x;
+	/* EPS_LatCtrlActive: start-bit 32, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x147_ADC_147.EPS_LatCtrlActive)) & 0x1;
+	x <<= 24; 
+	m |= x;
+	/* EspVehSpdVld: start-bit 60, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x147_ADC_147.EspVehSpdVld)) & 0x1;
+	x <<= 4; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x147_ADC_147_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x147_ADC_147(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* EpsSasSteerAg: start-bit 9, length 16, endianess motorola, scaling 0.1, offset 0 */
+	x = (m >> 34) & 0xffff;
+	o->can_0x147_ADC_147.EpsSasSteerAg = x;
+	/* EPS_Pinionang: start-bit 7, length 14, endianess motorola, scaling 0.1, offset -720 */
+	x = (m >> 50) & 0x3fff;
+	o->can_0x147_ADC_147.EPS_Pinionang = x;
+	/* EspVehSpd: start-bit 41, length 13, endianess motorola, scaling 0.05625, offset 0 */
+	x = (m >> 5) & 0x1fff;
+	o->can_0x147_ADC_147.EspVehSpd = x;
+	/* EpsSteerAgRate: start-bit 24, length 8, endianess motorola, scaling 4, offset 0 */
+	x = (m >> 25) & 0xff;
+	o->can_0x147_ADC_147.EpsSteerAgRate = x;
+	/* EPS_ADS_Abortfeedback: start-bit 45, length 4, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 18) & 0xf;
+	o->can_0x147_ADC_147.EPS_ADS_Abortfeedback = x;
+	/* EPS_LatCtrlAvailabilityStatus: start-bit 47, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 22) & 0x3;
+	o->can_0x147_ADC_147.EPS_LatCtrlAvailabilityStatus = x;
+	/* EpsSasSteerAgVld: start-bit 25, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 33) & 0x1;
+	o->can_0x147_ADC_147.EpsSasSteerAgVld = x;
+	/* EPS_LatCtrlActive: start-bit 32, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 24) & 0x1;
+	o->can_0x147_ADC_147.EPS_LatCtrlActive = x;
+	/* EspVehSpdVld: start-bit 60, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 4) & 0x1;
+	o->can_0x147_ADC_147.EspVehSpdVld = x;
+	o->can_0x147_ADC_147_rx = 1;
+	o->can_0x147_ADC_147_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x147_EpsSasSteerAg(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x147_ADC_147.EpsSasSteerAg);
+	rval *= 0.1;
+	if ((rval >= -780) && (rval <= 780)) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x147_EpsSasSteerAg(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x147_ADC_147.EpsSasSteerAg = 0;
+	if (in < -780)
+		return -1;
+	if (in > 780)
+		return -1;
+	in *= 10;
+	o->can_0x147_ADC_147.EpsSasSteerAg = in;
+	return 0;
+}
+
+int decode_can_0x147_EPS_Pinionang(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x147_ADC_147.EPS_Pinionang);
+	rval *= 0.1;
+	rval += -720;
+	if (rval <= 720) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x147_EPS_Pinionang(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x147_ADC_147.EPS_Pinionang = 0;
+	if (in > 720)
+		return -1;
+	in += 720;
+	in *= 10;
+	o->can_0x147_ADC_147.EPS_Pinionang = in;
+	return 0;
+}
+
+int decode_can_0x147_EspVehSpd(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x147_ADC_147.EspVehSpd);
+	rval *= 0.05625;
+	if (rval <= 460.744) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x147_EspVehSpd(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x147_ADC_147.EspVehSpd = 0;
+	if (in > 460.744)
+		return -1;
+	in *= 17.7778;
+	o->can_0x147_ADC_147.EspVehSpd = in;
+	return 0;
+}
+
+int decode_can_0x147_EpsSteerAgRate(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x147_ADC_147.EpsSteerAgRate);
+	rval *= 4;
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x147_EpsSteerAgRate(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	in *= 0.25;
+	o->can_0x147_ADC_147.EpsSteerAgRate = in;
+	return 0;
+}
+
+int decode_can_0x147_EPS_ADS_Abortfeedback(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x147_ADC_147.EPS_ADS_Abortfeedback);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x147_EPS_ADS_Abortfeedback(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x147_ADC_147.EPS_ADS_Abortfeedback = in;
+	return 0;
+}
+
+int decode_can_0x147_EPS_LatCtrlAvailabilityStatus(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x147_ADC_147.EPS_LatCtrlAvailabilityStatus);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x147_EPS_LatCtrlAvailabilityStatus(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x147_ADC_147.EPS_LatCtrlAvailabilityStatus = in;
+	return 0;
+}
+
+int decode_can_0x147_EpsSasSteerAgVld(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x147_ADC_147.EpsSasSteerAgVld);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x147_EpsSasSteerAgVld(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x147_ADC_147.EpsSasSteerAgVld = in;
+	return 0;
+}
+
+int decode_can_0x147_EPS_LatCtrlActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x147_ADC_147.EPS_LatCtrlActive);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x147_EPS_LatCtrlActive(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x147_ADC_147.EPS_LatCtrlActive = in;
+	return 0;
+}
+
+int decode_can_0x147_EspVehSpdVld(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x147_ADC_147.EspVehSpdVld);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x147_EspVehSpdVld(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x147_ADC_147.EspVehSpdVld = in;
+	return 0;
+}
+
+int print_can_0x147_ADC_147(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "EpsSasSteerAg = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EpsSasSteerAg)));
+	r = print_helper(r, fprintf(output, "EPS_Pinionang = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EPS_Pinionang)));
+	r = print_helper(r, fprintf(output, "EspVehSpd = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EspVehSpd)));
+	r = print_helper(r, fprintf(output, "EpsSteerAgRate = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EpsSteerAgRate)));
+	r = print_helper(r, fprintf(output, "EPS_ADS_Abortfeedback = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EPS_ADS_Abortfeedback)));
+	r = print_helper(r, fprintf(output, "EPS_LatCtrlAvailabilityStatus = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EPS_LatCtrlAvailabilityStatus)));
+	r = print_helper(r, fprintf(output, "EpsSasSteerAgVld = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EpsSasSteerAgVld)));
+	r = print_helper(r, fprintf(output, "EPS_LatCtrlActive = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EPS_LatCtrlActive)));
+	r = print_helper(r, fprintf(output, "EspVehSpdVld = (wire: %.0f)\n", (double)(o->can_0x147_ADC_147.EspVehSpdVld)));
+	return r;
+}
+
+static int pack_can_0x14a_ADC_14A(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* VcuPtTqLimMax: start-bit 7, length 16, endianess motorola, scaling 1, offset -32768 */
+	x = ((uint16_t)(o->can_0x14a_ADC_14A.VcuPtTqLimMax)) & 0xffff;
+	x <<= 48; 
+	m |= x;
+	/* VcuPtTqLimMin: start-bit 23, length 16, endianess motorola, scaling 1, offset -32768 */
+	x = ((uint16_t)(o->can_0x14a_ADC_14A.VcuPtTqLimMin)) & 0xffff;
+	x <<= 32; 
+	m |= x;
+	/* VcuPtTqReal: start-bit 39, length 16, endianess motorola, scaling 1, offset -32768 */
+	x = ((uint16_t)(o->can_0x14a_ADC_14A.VcuPtTqReal)) & 0xffff;
+	x <<= 16; 
+	m |= x;
+	/* VcuShiftLvlPosn: start-bit 50, length 4, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x14a_ADC_14A.VcuShiftLvlPosn)) & 0xf;
+	x <<= 7; 
+	m |= x;
+	/* IBCU_ReduceFuncAvail: start-bit 52, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x14a_ADC_14A.IBCU_ReduceFuncAvail)) & 0x3;
+	x <<= 11; 
+	m |= x;
+	/* IBCU_FullFuncAvail: start-bit 54, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x14a_ADC_14A.IBCU_FullFuncAvail)) & 0x3;
+	x <<= 13; 
+	m |= x;
+	/* ESP_BrakeForce: start-bit 55, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x14a_ADC_14A.ESP_BrakeForce)) & 0x1;
+	x <<= 15; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x14a_ADC_14A_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x14a_ADC_14A(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* VcuPtTqLimMax: start-bit 7, length 16, endianess motorola, scaling 1, offset -32768 */
+	x = (m >> 48) & 0xffff;
+	o->can_0x14a_ADC_14A.VcuPtTqLimMax = x;
+	/* VcuPtTqLimMin: start-bit 23, length 16, endianess motorola, scaling 1, offset -32768 */
+	x = (m >> 32) & 0xffff;
+	o->can_0x14a_ADC_14A.VcuPtTqLimMin = x;
+	/* VcuPtTqReal: start-bit 39, length 16, endianess motorola, scaling 1, offset -32768 */
+	x = (m >> 16) & 0xffff;
+	o->can_0x14a_ADC_14A.VcuPtTqReal = x;
+	/* VcuShiftLvlPosn: start-bit 50, length 4, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 7) & 0xf;
+	o->can_0x14a_ADC_14A.VcuShiftLvlPosn = x;
+	/* IBCU_ReduceFuncAvail: start-bit 52, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 11) & 0x3;
+	o->can_0x14a_ADC_14A.IBCU_ReduceFuncAvail = x;
+	/* IBCU_FullFuncAvail: start-bit 54, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 13) & 0x3;
+	o->can_0x14a_ADC_14A.IBCU_FullFuncAvail = x;
+	/* ESP_BrakeForce: start-bit 55, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 15) & 0x1;
+	o->can_0x14a_ADC_14A.ESP_BrakeForce = x;
+	o->can_0x14a_ADC_14A_rx = 1;
+	o->can_0x14a_ADC_14A_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x14a_VcuPtTqLimMax(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x14a_ADC_14A.VcuPtTqLimMax);
+	rval += -32768;
+	if (rval <= 32767) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x14a_VcuPtTqLimMax(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.VcuPtTqLimMax = 0;
+	if (in > 32767)
+		return -1;
+	in += 32768;
+	o->can_0x14a_ADC_14A.VcuPtTqLimMax = in;
+	return 0;
+}
+
+int decode_can_0x14a_VcuPtTqLimMin(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x14a_ADC_14A.VcuPtTqLimMin);
+	rval += -32768;
+	if (rval <= 32767) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x14a_VcuPtTqLimMin(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.VcuPtTqLimMin = 0;
+	if (in > 32767)
+		return -1;
+	in += 32768;
+	o->can_0x14a_ADC_14A.VcuPtTqLimMin = in;
+	return 0;
+}
+
+int decode_can_0x14a_VcuPtTqReal(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x14a_ADC_14A.VcuPtTqReal);
+	rval += -32768;
+	if (rval <= 32767) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x14a_VcuPtTqReal(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.VcuPtTqReal = 0;
+	if (in > 32767)
+		return -1;
+	in += 32768;
+	o->can_0x14a_ADC_14A.VcuPtTqReal = in;
+	return 0;
+}
+
+int decode_can_0x14a_VcuShiftLvlPosn(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x14a_ADC_14A.VcuShiftLvlPosn);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x14a_VcuShiftLvlPosn(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.VcuShiftLvlPosn = in;
+	return 0;
+}
+
+int decode_can_0x14a_IBCU_ReduceFuncAvail(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x14a_ADC_14A.IBCU_ReduceFuncAvail);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x14a_IBCU_ReduceFuncAvail(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.IBCU_ReduceFuncAvail = in;
+	return 0;
+}
+
+int decode_can_0x14a_IBCU_FullFuncAvail(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x14a_ADC_14A.IBCU_FullFuncAvail);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x14a_IBCU_FullFuncAvail(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.IBCU_FullFuncAvail = in;
+	return 0;
+}
+
+int decode_can_0x14a_ESP_BrakeForce(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x14a_ADC_14A.ESP_BrakeForce);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x14a_ESP_BrakeForce(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x14a_ADC_14A.ESP_BrakeForce = in;
+	return 0;
+}
+
+int print_can_0x14a_ADC_14A(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "VcuPtTqLimMax = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.VcuPtTqLimMax)));
+	r = print_helper(r, fprintf(output, "VcuPtTqLimMin = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.VcuPtTqLimMin)));
+	r = print_helper(r, fprintf(output, "VcuPtTqReal = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.VcuPtTqReal)));
+	r = print_helper(r, fprintf(output, "VcuShiftLvlPosn = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.VcuShiftLvlPosn)));
+	r = print_helper(r, fprintf(output, "IBCU_ReduceFuncAvail = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.IBCU_ReduceFuncAvail)));
+	r = print_helper(r, fprintf(output, "IBCU_FullFuncAvail = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.IBCU_FullFuncAvail)));
+	r = print_helper(r, fprintf(output, "ESP_BrakeForce = (wire: %.0f)\n", (double)(o->can_0x14a_ADC_14A.ESP_BrakeForce)));
+	return r;
+}
+
+static int pack_can_0x24b_ECU_24B(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* ACC_AEBTargetDeceleration: start-bit 24, length 16, endianess motorola, scaling 0.0005, offset -16 */
+	x = ((uint16_t)(o->can_0x24b_ECU_24B.ACC_AEBTargetDeceleration)) & 0xffff;
+	x <<= 17; 
+	m |= x;
+	/* ACC_AccTrqReq: start-bit 7, length 15, endianess motorola, scaling 1, offset -16384 */
+	x = ((uint16_t)(o->can_0x24b_ECU_24B.ACC_AccTrqReq)) & 0x7fff;
+	x <<= 49; 
+	m |= x;
+	/* ACC_ACCTargetAcceleration: start-bit 20, length 8, endianess motorola, scaling 0.05, offset -10 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_ACCTargetAcceleration)) & 0xff;
+	x <<= 37; 
+	m |= x;
+	/* ACC_ACCMode: start-bit 58, length 3, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_ACCMode)) & 0x7;
+	m |= x;
+	/* ADCReqMode: start-bit 50, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ADCReqMode)) & 0x3;
+	x <<= 9; 
+	m |= x;
+	/* ACC_AccTrqReqActive: start-bit 8, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_AccTrqReqActive)) & 0x1;
+	x <<= 48; 
+	m |= x;
+	/* ACC_AEBVehilceHoldReq: start-bit 40, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_AEBVehilceHoldReq)) & 0x1;
+	x <<= 16; 
+	m |= x;
+	/* ACC_AEBActive: start-bit 51, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_AEBActive)) & 0x1;
+	x <<= 11; 
+	m |= x;
+	/* ACC_Driveoff_Request: start-bit 53, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_Driveoff_Request)) & 0x1;
+	x <<= 13; 
+	m |= x;
+	/* ACC_DecToStop: start-bit 54, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_DecToStop)) & 0x1;
+	x <<= 14; 
+	m |= x;
+	/* ACC_CDDActive: start-bit 55, length 1, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x24b_ECU_24B.ACC_CDDActive)) & 0x1;
+	x <<= 15; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x24b_ECU_24B_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x24b_ECU_24B(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* ACC_AEBTargetDeceleration: start-bit 24, length 16, endianess motorola, scaling 0.0005, offset -16 */
+	x = (m >> 17) & 0xffff;
+	o->can_0x24b_ECU_24B.ACC_AEBTargetDeceleration = x;
+	/* ACC_AccTrqReq: start-bit 7, length 15, endianess motorola, scaling 1, offset -16384 */
+	x = (m >> 49) & 0x7fff;
+	o->can_0x24b_ECU_24B.ACC_AccTrqReq = x;
+	/* ACC_ACCTargetAcceleration: start-bit 20, length 8, endianess motorola, scaling 0.05, offset -10 */
+	x = (m >> 37) & 0xff;
+	o->can_0x24b_ECU_24B.ACC_ACCTargetAcceleration = x;
+	/* ACC_ACCMode: start-bit 58, length 3, endianess motorola, scaling 1, offset 0 */
+	x = m & 0x7;
+	o->can_0x24b_ECU_24B.ACC_ACCMode = x;
+	/* ADCReqMode: start-bit 50, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 9) & 0x3;
+	o->can_0x24b_ECU_24B.ADCReqMode = x;
+	/* ACC_AccTrqReqActive: start-bit 8, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 48) & 0x1;
+	o->can_0x24b_ECU_24B.ACC_AccTrqReqActive = x;
+	/* ACC_AEBVehilceHoldReq: start-bit 40, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 16) & 0x1;
+	o->can_0x24b_ECU_24B.ACC_AEBVehilceHoldReq = x;
+	/* ACC_AEBActive: start-bit 51, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 11) & 0x1;
+	o->can_0x24b_ECU_24B.ACC_AEBActive = x;
+	/* ACC_Driveoff_Request: start-bit 53, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 13) & 0x1;
+	o->can_0x24b_ECU_24B.ACC_Driveoff_Request = x;
+	/* ACC_DecToStop: start-bit 54, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 14) & 0x1;
+	o->can_0x24b_ECU_24B.ACC_DecToStop = x;
+	/* ACC_CDDActive: start-bit 55, length 1, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 15) & 0x1;
+	o->can_0x24b_ECU_24B.ACC_CDDActive = x;
+	o->can_0x24b_ECU_24B_rx = 1;
+	o->can_0x24b_ECU_24B_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_AEBTargetDeceleration(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x24b_ECU_24B.ACC_AEBTargetDeceleration);
+	rval *= 0.0005;
+	rval += -16;
+	if (rval <= 16) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x24b_ACC_AEBTargetDeceleration(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_AEBTargetDeceleration = 0;
+	if (in > 16)
+		return -1;
+	in += 16;
+	in *= 2000;
+	o->can_0x24b_ECU_24B.ACC_AEBTargetDeceleration = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_AccTrqReq(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x24b_ECU_24B.ACC_AccTrqReq);
+	rval += -16384;
+	if (rval <= 16383) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x24b_ACC_AccTrqReq(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_AccTrqReq = 0;
+	if (in > 16383)
+		return -1;
+	in += 16384;
+	o->can_0x24b_ECU_24B.ACC_AccTrqReq = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_ACCTargetAcceleration(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x24b_ECU_24B.ACC_ACCTargetAcceleration);
+	rval *= 0.05;
+	rval += -10;
+	if (rval <= 2.75) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x24b_ACC_ACCTargetAcceleration(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_ACCTargetAcceleration = 0;
+	if (in > 2.75)
+		return -1;
+	in += 10;
+	in *= 20;
+	o->can_0x24b_ECU_24B.ACC_ACCTargetAcceleration = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_ACCMode(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_ACCMode);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_ACCMode(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_ACCMode = in;
+	return 0;
+}
+
+int decode_can_0x24b_ADCReqMode(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ADCReqMode);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ADCReqMode(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ADCReqMode = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_AccTrqReqActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_AccTrqReqActive);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_AccTrqReqActive(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_AccTrqReqActive = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_AEBVehilceHoldReq(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_AEBVehilceHoldReq);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_AEBVehilceHoldReq(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_AEBVehilceHoldReq = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_AEBActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_AEBActive);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_AEBActive(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_AEBActive = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_Driveoff_Request(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_Driveoff_Request);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_Driveoff_Request(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_Driveoff_Request = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_DecToStop(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_DecToStop);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_DecToStop(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_DecToStop = in;
+	return 0;
+}
+
+int decode_can_0x24b_ACC_CDDActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x24b_ECU_24B.ACC_CDDActive);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x24b_ACC_CDDActive(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x24b_ECU_24B.ACC_CDDActive = in;
+	return 0;
+}
+
+int print_can_0x24b_ECU_24B(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "ACC_AEBTargetDeceleration = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_AEBTargetDeceleration)));
+	r = print_helper(r, fprintf(output, "ACC_AccTrqReq = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_AccTrqReq)));
+	r = print_helper(r, fprintf(output, "ACC_ACCTargetAcceleration = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_ACCTargetAcceleration)));
+	r = print_helper(r, fprintf(output, "ACC_ACCMode = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_ACCMode)));
+	r = print_helper(r, fprintf(output, "ADCReqMode = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ADCReqMode)));
+	r = print_helper(r, fprintf(output, "ACC_AccTrqReqActive = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_AccTrqReqActive)));
+	r = print_helper(r, fprintf(output, "ACC_AEBVehilceHoldReq = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_AEBVehilceHoldReq)));
+	r = print_helper(r, fprintf(output, "ACC_AEBActive = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_AEBActive)));
+	r = print_helper(r, fprintf(output, "ACC_Driveoff_Request = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_Driveoff_Request)));
+	r = print_helper(r, fprintf(output, "ACC_DecToStop = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_DecToStop)));
+	r = print_helper(r, fprintf(output, "ACC_CDDActive = (wire: %.0f)\n", (double)(o->can_0x24b_ECU_24B.ACC_CDDActive)));
+	return r;
+}
+
+static int pack_can_0x250_ADC_250(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* ESP_YawRate: start-bit 2, length 14, endianess motorola, scaling 0.01, offset -81.91 */
+	x = ((uint16_t)(o->can_0x250_ADC_250.ESP_YawRate)) & 0x3fff;
+	x <<= 45; 
+	m |= x;
+	/* ESP_LongAccel: start-bit 20, length 10, endianess motorola, scaling 0.03125, offset -16 */
+	x = ((uint16_t)(o->can_0x250_ADC_250.ESP_LongAccel)) & 0x3ff;
+	x <<= 35; 
+	m |= x;
+	/* ESP_LatAccel: start-bit 24, length 8, endianess motorola, scaling 0.1, offset -12.7 */
+	x = ((uint8_t)(o->can_0x250_ADC_250.ESP_LatAccel)) & 0xff;
+	x <<= 25; 
+	m |= x;
+	/* EPS_ADS_ControlFeedback: start-bit 7, length 3, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x250_ADC_250.EPS_ADS_ControlFeedback)) & 0x7;
+	x <<= 61; 
+	m |= x;
+	/* ESP_YawRateValid: start-bit 4, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x250_ADC_250.ESP_YawRateValid)) & 0x3;
+	x <<= 59; 
+	m |= x;
+	/* ESP_LongAccelValid: start-bit 26, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x250_ADC_250.ESP_LongAccelValid)) & 0x3;
+	x <<= 33; 
+	m |= x;
+	/* ESP_LatAccelValid: start-bit 32, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x250_ADC_250.ESP_LatAccelValid)) & 0x3;
+	x <<= 23; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x250_ADC_250_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x250_ADC_250(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* ESP_YawRate: start-bit 2, length 14, endianess motorola, scaling 0.01, offset -81.91 */
+	x = (m >> 45) & 0x3fff;
+	o->can_0x250_ADC_250.ESP_YawRate = x;
+	/* ESP_LongAccel: start-bit 20, length 10, endianess motorola, scaling 0.03125, offset -16 */
+	x = (m >> 35) & 0x3ff;
+	o->can_0x250_ADC_250.ESP_LongAccel = x;
+	/* ESP_LatAccel: start-bit 24, length 8, endianess motorola, scaling 0.1, offset -12.7 */
+	x = (m >> 25) & 0xff;
+	o->can_0x250_ADC_250.ESP_LatAccel = x;
+	/* EPS_ADS_ControlFeedback: start-bit 7, length 3, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 61) & 0x7;
+	o->can_0x250_ADC_250.EPS_ADS_ControlFeedback = x;
+	/* ESP_YawRateValid: start-bit 4, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 59) & 0x3;
+	o->can_0x250_ADC_250.ESP_YawRateValid = x;
+	/* ESP_LongAccelValid: start-bit 26, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 33) & 0x3;
+	o->can_0x250_ADC_250.ESP_LongAccelValid = x;
+	/* ESP_LatAccelValid: start-bit 32, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 23) & 0x3;
+	o->can_0x250_ADC_250.ESP_LatAccelValid = x;
+	o->can_0x250_ADC_250_rx = 1;
+	o->can_0x250_ADC_250_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x250_ESP_YawRate(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x250_ADC_250.ESP_YawRate);
+	rval *= 0.01;
+	rval += -81.91;
+	if (rval <= 81.92) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x250_ESP_YawRate(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x250_ADC_250.ESP_YawRate = 0;
+	if (in > 81.92)
+		return -1;
+	in += 81.91;
+	in *= 100;
+	o->can_0x250_ADC_250.ESP_YawRate = in;
+	return 0;
+}
+
+int decode_can_0x250_ESP_LongAccel(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x250_ADC_250.ESP_LongAccel);
+	rval *= 0.03125;
+	rval += -16;
+	if (rval <= 15.9062) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x250_ESP_LongAccel(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x250_ADC_250.ESP_LongAccel = 0;
+	if (in > 15.9062)
+		return -1;
+	in += 16;
+	in *= 32;
+	o->can_0x250_ADC_250.ESP_LongAccel = in;
+	return 0;
+}
+
+int decode_can_0x250_ESP_LatAccel(const can_obj_bcan_dbc_h_t *o, double *out) {
+	assert(o);
+	assert(out);
+	double rval = (double)(o->can_0x250_ADC_250.ESP_LatAccel);
+	rval *= 0.1;
+	rval += -12.7;
+	if (rval <= 12.7) {
+		*out = rval;
+		return 0;
+	} else {
+		*out = (double)0;
+		return -1;
+	}
+}
+
+int encode_can_0x250_ESP_LatAccel(can_obj_bcan_dbc_h_t *o, double in) {
+	assert(o);
+	o->can_0x250_ADC_250.ESP_LatAccel = 0;
+	if (in > 12.7)
+		return -1;
+	in += 12.7;
+	in *= 10;
+	o->can_0x250_ADC_250.ESP_LatAccel = in;
+	return 0;
+}
+
+int decode_can_0x250_EPS_ADS_ControlFeedback(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x250_ADC_250.EPS_ADS_ControlFeedback);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x250_EPS_ADS_ControlFeedback(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x250_ADC_250.EPS_ADS_ControlFeedback = in;
+	return 0;
+}
+
+int decode_can_0x250_ESP_YawRateValid(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x250_ADC_250.ESP_YawRateValid);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x250_ESP_YawRateValid(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x250_ADC_250.ESP_YawRateValid = in;
+	return 0;
+}
+
+int decode_can_0x250_ESP_LongAccelValid(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x250_ADC_250.ESP_LongAccelValid);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x250_ESP_LongAccelValid(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x250_ADC_250.ESP_LongAccelValid = in;
+	return 0;
+}
+
+int decode_can_0x250_ESP_LatAccelValid(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x250_ADC_250.ESP_LatAccelValid);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x250_ESP_LatAccelValid(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x250_ADC_250.ESP_LatAccelValid = in;
+	return 0;
+}
+
+int print_can_0x250_ADC_250(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "ESP_YawRate = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.ESP_YawRate)));
+	r = print_helper(r, fprintf(output, "ESP_LongAccel = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.ESP_LongAccel)));
+	r = print_helper(r, fprintf(output, "ESP_LatAccel = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.ESP_LatAccel)));
+	r = print_helper(r, fprintf(output, "EPS_ADS_ControlFeedback = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.EPS_ADS_ControlFeedback)));
+	r = print_helper(r, fprintf(output, "ESP_YawRateValid = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.ESP_YawRateValid)));
+	r = print_helper(r, fprintf(output, "ESP_LongAccelValid = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.ESP_LongAccelValid)));
+	r = print_helper(r, fprintf(output, "ESP_LatAccelValid = (wire: %.0f)\n", (double)(o->can_0x250_ADC_250.ESP_LatAccelValid)));
+	return r;
+}
+
+static int pack_can_0x358_ADC_358(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* ADS_UDLCTurnLightReq: start-bit 26, length 3, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x358_ADC_358.ADS_UDLCTurnLightReq)) & 0x7;
+	x <<= 32; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x358_ADC_358_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x358_ADC_358(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* ADS_UDLCTurnLightReq: start-bit 26, length 3, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 32) & 0x7;
+	o->can_0x358_ADC_358.ADS_UDLCTurnLightReq = x;
+	o->can_0x358_ADC_358_rx = 1;
+	o->can_0x358_ADC_358_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x358_ADS_UDLCTurnLightReq(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x358_ADC_358.ADS_UDLCTurnLightReq);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x358_ADS_UDLCTurnLightReq(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x358_ADC_358.ADS_UDLCTurnLightReq = in;
+	return 0;
+}
+
+int print_can_0x358_ADC_358(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "ADS_UDLCTurnLightReq = (wire: %.0f)\n", (double)(o->can_0x358_ADC_358.ADS_UDLCTurnLightReq)));
+	return r;
+}
+
+static int pack_can_0x36e_ECU_36E(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* ADS_UDLCTurnLightReq: start-bit 7, length 3, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x36e_ECU_36E.ADS_UDLCTurnLightReq)) & 0x7;
+	x <<= 61; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x36e_ECU_36E_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x36e_ECU_36E(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* ADS_UDLCTurnLightReq: start-bit 7, length 3, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 61) & 0x7;
+	o->can_0x36e_ECU_36E.ADS_UDLCTurnLightReq = x;
+	o->can_0x36e_ECU_36E_rx = 1;
+	o->can_0x36e_ECU_36E_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x36e_ADS_UDLCTurnLightReq(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x36e_ECU_36E.ADS_UDLCTurnLightReq);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x36e_ADS_UDLCTurnLightReq(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x36e_ECU_36E.ADS_UDLCTurnLightReq = in;
+	return 0;
+}
+
+int print_can_0x36e_ECU_36E(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "ADS_UDLCTurnLightReq = (wire: %.0f)\n", (double)(o->can_0x36e_ECU_36E.ADS_UDLCTurnLightReq)));
+	return r;
+}
+
+static int pack_can_0x3aa_ADC_3AA(can_obj_bcan_dbc_h_t *o, uint64_t *data) {
+	assert(o);
+	assert(data);
+	register uint64_t x;
+	register uint64_t m = 0;
+	/* VcuCrsSetSwtSts: start-bit 3, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x3aa_ADC_3AA.VcuCrsSetSwtSts)) & 0x3;
+	x <<= 58; 
+	m |= x;
+	/* VcuCrsResuSwtSts: start-bit 5, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x3aa_ADC_3AA.VcuCrsResuSwtSts)) & 0x3;
+	x <<= 60; 
+	m |= x;
+	/* VcuCrsDstSwtPlusSts: start-bit 7, length 2, endianess motorola, scaling 1, offset 0 */
+	x = ((uint8_t)(o->can_0x3aa_ADC_3AA.VcuCrsDstSwtPlusSts)) & 0x3;
+	x <<= 62; 
+	m |= x;
+	*data = reverse_byte_order(m);
+	o->can_0x3aa_ADC_3AA_tx = 1;
+	return 0;
+}
+
+static int unpack_can_0x3aa_ADC_3AA(can_obj_bcan_dbc_h_t *o, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(dlc <= 8);
+	register uint64_t x;
+	register uint64_t m = reverse_byte_order(data);
+	if (dlc < 8)
+		return -1;
+	/* VcuCrsSetSwtSts: start-bit 3, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 58) & 0x3;
+	o->can_0x3aa_ADC_3AA.VcuCrsSetSwtSts = x;
+	/* VcuCrsResuSwtSts: start-bit 5, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 60) & 0x3;
+	o->can_0x3aa_ADC_3AA.VcuCrsResuSwtSts = x;
+	/* VcuCrsDstSwtPlusSts: start-bit 7, length 2, endianess motorola, scaling 1, offset 0 */
+	x = (m >> 62) & 0x3;
+	o->can_0x3aa_ADC_3AA.VcuCrsDstSwtPlusSts = x;
+	o->can_0x3aa_ADC_3AA_rx = 1;
+	o->can_0x3aa_ADC_3AA_time_stamp_rx = time_stamp;
+	return 0;
+}
+
+int decode_can_0x3aa_VcuCrsSetSwtSts(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x3aa_ADC_3AA.VcuCrsSetSwtSts);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x3aa_VcuCrsSetSwtSts(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x3aa_ADC_3AA.VcuCrsSetSwtSts = in;
+	return 0;
+}
+
+int decode_can_0x3aa_VcuCrsResuSwtSts(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x3aa_ADC_3AA.VcuCrsResuSwtSts);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x3aa_VcuCrsResuSwtSts(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x3aa_ADC_3AA.VcuCrsResuSwtSts = in;
+	return 0;
+}
+
+int decode_can_0x3aa_VcuCrsDstSwtPlusSts(const can_obj_bcan_dbc_h_t *o, uint8_t *out) {
+	assert(o);
+	assert(out);
+	uint8_t rval = (uint8_t)(o->can_0x3aa_ADC_3AA.VcuCrsDstSwtPlusSts);
+	*out = rval;
+	return 0;
+}
+
+int encode_can_0x3aa_VcuCrsDstSwtPlusSts(can_obj_bcan_dbc_h_t *o, uint8_t in) {
+	assert(o);
+	o->can_0x3aa_ADC_3AA.VcuCrsDstSwtPlusSts = in;
+	return 0;
+}
+
+int print_can_0x3aa_ADC_3AA(const can_obj_bcan_dbc_h_t *o, FILE *output) {
+	assert(o);
+	assert(output);
+	int r = 0;
+	r = print_helper(r, fprintf(output, "VcuCrsSetSwtSts = (wire: %.0f)\n", (double)(o->can_0x3aa_ADC_3AA.VcuCrsSetSwtSts)));
+	r = print_helper(r, fprintf(output, "VcuCrsResuSwtSts = (wire: %.0f)\n", (double)(o->can_0x3aa_ADC_3AA.VcuCrsResuSwtSts)));
+	r = print_helper(r, fprintf(output, "VcuCrsDstSwtPlusSts = (wire: %.0f)\n", (double)(o->can_0x3aa_ADC_3AA.VcuCrsDstSwtPlusSts)));
+	return r;
+}
+
+int unpack_message(can_obj_bcan_dbc_h_t *o, const unsigned long id, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp) {
+	assert(o);
+	assert(id < (1ul << 29)); /* 29-bit CAN ID is largest possible */
+	assert(dlc <= 8);         /* Maximum of 8 bytes in a CAN packet */
+	switch (id) {
+	case 0x144: return unpack_can_0x144_ECU_144(o, data, dlc, time_stamp);
+	case 0x147: return unpack_can_0x147_ADC_147(o, data, dlc, time_stamp);
+	case 0x14a: return unpack_can_0x14a_ADC_14A(o, data, dlc, time_stamp);
+	case 0x24b: return unpack_can_0x24b_ECU_24B(o, data, dlc, time_stamp);
+	case 0x250: return unpack_can_0x250_ADC_250(o, data, dlc, time_stamp);
+	case 0x358: return unpack_can_0x358_ADC_358(o, data, dlc, time_stamp);
+	case 0x36e: return unpack_can_0x36e_ECU_36E(o, data, dlc, time_stamp);
+	case 0x3aa: return unpack_can_0x3aa_ADC_3AA(o, data, dlc, time_stamp);
+	default: break; 
+	}
+	return -1; 
+}
+
+int pack_message(can_obj_bcan_dbc_h_t *o, const unsigned long id, uint64_t *data) {
+	assert(o);
+	assert(id < (1ul << 29)); /* 29-bit CAN ID is largest possible */
+	switch (id) {
+	case 0x144: return pack_can_0x144_ECU_144(o, data);
+	case 0x147: return pack_can_0x147_ADC_147(o, data);
+	case 0x14a: return pack_can_0x14a_ADC_14A(o, data);
+	case 0x24b: return pack_can_0x24b_ECU_24B(o, data);
+	case 0x250: return pack_can_0x250_ADC_250(o, data);
+	case 0x358: return pack_can_0x358_ADC_358(o, data);
+	case 0x36e: return pack_can_0x36e_ECU_36E(o, data);
+	case 0x3aa: return pack_can_0x3aa_ADC_3AA(o, data);
+	default: break; 
+	}
+	return -1; 
+}
+
+int print_message(const can_obj_bcan_dbc_h_t *o, const unsigned long id, FILE *output) {
+	assert(o);
+	assert(id < (1ul << 29)); /* 29-bit CAN ID is largest possible */
+	assert(output);
+	switch (id) {
+	case 0x144: return print_can_0x144_ECU_144(o, output);
+	case 0x147: return print_can_0x147_ADC_147(o, output);
+	case 0x14a: return print_can_0x14a_ADC_14A(o, output);
+	case 0x24b: return print_can_0x24b_ECU_24B(o, output);
+	case 0x250: return print_can_0x250_ADC_250(o, output);
+	case 0x358: return print_can_0x358_ADC_358(o, output);
+	case 0x36e: return print_can_0x36e_ECU_36E(o, output);
+	case 0x3aa: return print_can_0x3aa_ADC_3AA(o, output);
+	default: break; 
+	}
+	return -1; 
+}
+

+ 389 - 0
src/controller/controller_changan_shenlan_v2/BCAN_dbc.h

@@ -0,0 +1,389 @@
+#ifndef BCAN_DBC_H
+#define BCAN_DBC_H
+
+#include <stdint.h>
+#include <stdio.h>
+
+#ifdef __cplusplus
+extern "C" { 
+#endif
+
+#ifndef PREPACK
+#define PREPACK
+#endif
+
+#ifndef POSTPACK
+#define POSTPACK
+#endif
+
+#ifndef DBCC_TIME_STAMP
+#define DBCC_TIME_STAMP
+typedef uint32_t dbcc_time_stamp_t; /* Time stamp for message; you decide on units */
+#endif
+
+#ifndef DBCC_STATUS_ENUM
+#define DBCC_STATUS_ENUM
+typedef enum {
+	DBCC_SIG_STAT_UNINITIALIZED_E = 0, /* Message never sent/received */
+	DBCC_SIG_STAT_OK_E            = 1, /* Message ok */
+	DBCC_SIG_STAT_ERROR_E         = 2, /* Encode/Decode/Timestamp/Any error */
+} dbcc_signal_status_e;
+#endif
+
+typedef enum {
+	ACC_ADCReqType__e = 0,
+} ACC_ADCReqType_e;
+
+typedef enum {
+	ACC_LatAngReqActive__e = 0,
+} ACC_LatAngReqActive_e;
+
+typedef enum {
+	ADS_Reqmode__e = 0,
+} ADS_Reqmode_e;
+
+typedef enum {
+	EspVehSpdVld__e = 0,
+} EspVehSpdVld_e;
+
+typedef enum {
+	EPS_ADS_Abortfeedback__e = 0,
+} EPS_ADS_Abortfeedback_e;
+
+typedef enum {
+	EPS_LatCtrlAvailabilityStatus__e = 0,
+} EPS_LatCtrlAvailabilityStatus_e;
+
+typedef enum {
+	EPS_LatCtrlActive__e = 0,
+} EPS_LatCtrlActive_e;
+
+typedef enum {
+	EpsSasSteerAgVld__e = 0,
+} EpsSasSteerAgVld_e;
+
+typedef enum {
+	ESP_LatAccelValid__e = 0,
+} ESP_LatAccelValid_e;
+
+typedef enum {
+	ESP_LongAccelValid__e = 0,
+} ESP_LongAccelValid_e;
+
+typedef enum {
+	ESP_YawRateValid__e = 0,
+} ESP_YawRateValid_e;
+
+typedef enum {
+	EPS_ADS_ControlFeedback__e = 0,
+} EPS_ADS_ControlFeedback_e;
+
+typedef enum {
+	VcuShiftLvlPosn__e = 0,
+} VcuShiftLvlPosn_e;
+
+typedef enum {
+	IBCU_ReduceFuncAvail__e = 0,
+} IBCU_ReduceFuncAvail_e;
+
+typedef enum {
+	IBCU_FullFuncAvail__e = 0,
+} IBCU_FullFuncAvail_e;
+
+typedef enum {
+	ESP_BrakeForce__e = 0,
+} ESP_BrakeForce_e;
+
+typedef enum {
+	ACC_ACCMode__e = 0,
+} ACC_ACCMode_e;
+
+typedef enum {
+	ADCReqMode__e = 1,
+} ADCReqMode_e;
+
+typedef enum {
+	ACC_AEBActive__e = 0,
+} ACC_AEBActive_e;
+
+typedef enum {
+	ACC_Driveoff_Request__e = 0,
+} ACC_Driveoff_Request_e;
+
+typedef enum {
+	ACC_DecToStop__e = 0,
+} ACC_DecToStop_e;
+
+typedef enum {
+	ACC_CDDActive__e = 0,
+} ACC_CDDActive_e;
+
+typedef enum {
+	ACC_AEBVehilceHoldReq__e = 0,
+} ACC_AEBVehilceHoldReq_e;
+
+typedef enum {
+	ACC_AccTrqReqActive__e = 0,
+} ACC_AccTrqReqActive_e;
+
+typedef enum {
+	ADS_UDLCTurnLightReq__e = 0,
+} ADS_UDLCTurnLightReq_e;
+
+typedef enum {
+	VcuCrsSetSwtSts__e = 0,
+} VcuCrsSetSwtSts_e;
+
+typedef enum {
+	VcuCrsResuSwtSts__e = 0,
+} VcuCrsResuSwtSts_e;
+
+typedef enum {
+	VcuCrsDstSwtPlusSts__e = 0,
+} VcuCrsDstSwtPlusSts_e;
+
+typedef enum {
+	ADS_UDLCTurnLightReq__e = 0,
+} ADS_UDLCTurnLightReq_e;
+
+/* CAN  */
+typedef PREPACK struct {
+	uint16_t ACC_LatAngReq; /* 方向盘往零点左转为正,零点右转为负   0x3841-3FFF:Reserved   scaling 0.1, offset -720.0, units degree  */
+	uint16_t ACC_MotorTorqueMaxLimitRequest; /*方向盘左打为正。在EPS ECU 开始助力之前、Initial 值输出为(0)。0x7FF:Reserved  scaling 0.0, offset -20.5, units Nm  */
+	uint16_t ACC_MotorTorqueMinLimitRequest; /* 方向盘左打为正。在EPS ECU 开始助力之前、Initial 值输出为(0)。0x7FF:Reserved scaling 0.0, offset -20.5, units Nm  */
+	uint8_t ADS_Reqmode; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_ADCReqType; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_LatAngReqActive; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x144_ECU_144_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	int16_t EpsSasSteerAg; /* scaling 0.1, offset 0.0, units degree  */
+	uint16_t EPS_Pinionang; /* 方向盘往零点左转为正,零点右转为负 0x384A-3FFF=Reserved  scaling 0.1, offset -720.0, units degree  */
+	uint16_t EspVehSpd; /* 187   scaling 0.1, offset 0.0, units km/h  */
+	uint8_t EpsSteerAgRate; /* scaling 4.0, offset 0.0, units deg/s  */
+	uint8_t EPS_ADS_Abortfeedback; /* 建议行车泊车分开 scaling 1.0, offset 0.0, units none  */
+	uint8_t EPS_LatCtrlAvailabilityStatus; /* 平台为10ms,CD569特例为8ms  scaling 1.0, offset 0.0, units none  */
+	uint8_t EpsSasSteerAgVld; /* 方向盘往零点左转为正,零点右转为负 SteeringAngleSpeed (N:valueofthemessage): :N×4,for0<N≤254 :errorsignaled,forN>254  scaling 1.0, offset 0.0, units none  */
+	uint8_t EPS_LatCtrlActive; /*  平台为10ms,CD569特例为8ms   scaling 1.0, offset 0.0, units none  */
+	uint8_t EspVehSpdVld; /* 187  scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x147_ADC_147_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	uint16_t VcuPtTqLimMax; /* scaling 1.0, offset -32768.0, units Nm  */
+	uint16_t VcuPtTqLimMin; /* scaling 1.0, offset -32768.0, units Nm  */
+	uint16_t VcuPtTqReal; /* scaling 1.0, offset -32768.0, units Nm  */
+	uint8_t VcuShiftLvlPosn; /*  0x5~0xE:Reserved  scaling 1.0, offset 0.0, units none  */
+	uint8_t IBCU_ReduceFuncAvail; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t IBCU_FullFuncAvail; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ESP_BrakeForce; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x14a_ADC_14A_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	/* ACC_AEBTargetDeceleration: target deceleration value from AEB/EBA/FCTB/RCTB  */
+	/* scaling 0.0, offset -16.0, units m/s2  */
+	uint16_t ACC_AEBTargetDeceleration;
+	uint16_t ACC_AccTrqReq; /* scaling 1.0, offset -16384.0, units Nm  */
+	/* ACC_ACCTargetAcceleration: ACC target acceleration for transmission.  */
+	/* scaling 0.1, offset -10.0, units m/s2  */
+	uint8_t ACC_ACCTargetAcceleration;
+	uint8_t ACC_ACCMode; /* scaling 1.0, offset 0.0, units none  */
+	/* ADCReqMode:   */
+	/* scaling 1.0, offset 0.0, units none  */
+	uint8_t ADCReqMode;
+	uint8_t ACC_AccTrqReqActive; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_AEBVehilceHoldReq; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_AEBActive; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_Driveoff_Request; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_DecToStop; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ACC_CDDActive; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x24b_ECU_24B_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	uint16_t ESP_YawRate; /* scaling 0.0, offset -81.9, units degree/s  */
+	uint16_t ESP_LongAccel; /* scaling 0.0, offset -16.0, units m/s2  */
+	uint8_t ESP_LatAccel; /* scaling 0.1, offset -12.7, units m/s2  */
+	uint8_t EPS_ADS_ControlFeedback; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ESP_YawRateValid; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ESP_LongAccelValid; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t ESP_LatAccelValid; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x250_ADC_250_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	uint8_t ADS_UDLCTurnLightReq; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x358_ADC_358_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	uint8_t ADS_UDLCTurnLightReq; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x36e_ECU_36E_t;
+
+/* CAN  */
+typedef PREPACK struct {
+	uint8_t VcuCrsSetSwtSts; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t VcuCrsResuSwtSts; /* scaling 1.0, offset 0.0, units none  */
+	uint8_t VcuCrsDstSwtPlusSts; /* scaling 1.0, offset 0.0, units none  */
+} POSTPACK can_0x3aa_ADC_3AA_t;
+
+typedef PREPACK struct {
+	dbcc_time_stamp_t can_0x144_ECU_144_time_stamp_rx;
+	dbcc_time_stamp_t can_0x147_ADC_147_time_stamp_rx;
+	dbcc_time_stamp_t can_0x14a_ADC_14A_time_stamp_rx;
+	dbcc_time_stamp_t can_0x24b_ECU_24B_time_stamp_rx;
+	dbcc_time_stamp_t can_0x250_ADC_250_time_stamp_rx;
+	dbcc_time_stamp_t can_0x358_ADC_358_time_stamp_rx;
+	dbcc_time_stamp_t can_0x36e_ECU_36E_time_stamp_rx;
+	dbcc_time_stamp_t can_0x3aa_ADC_3AA_time_stamp_rx;
+	unsigned can_0x144_ECU_144_status : 2;
+	unsigned can_0x144_ECU_144_tx : 1;
+	unsigned can_0x144_ECU_144_rx : 1;
+	unsigned can_0x147_ADC_147_status : 2;
+	unsigned can_0x147_ADC_147_tx : 1;
+	unsigned can_0x147_ADC_147_rx : 1;
+	unsigned can_0x14a_ADC_14A_status : 2;
+	unsigned can_0x14a_ADC_14A_tx : 1;
+	unsigned can_0x14a_ADC_14A_rx : 1;
+	unsigned can_0x24b_ECU_24B_status : 2;
+	unsigned can_0x24b_ECU_24B_tx : 1;
+	unsigned can_0x24b_ECU_24B_rx : 1;
+	unsigned can_0x250_ADC_250_status : 2;
+	unsigned can_0x250_ADC_250_tx : 1;
+	unsigned can_0x250_ADC_250_rx : 1;
+	unsigned can_0x358_ADC_358_status : 2;
+	unsigned can_0x358_ADC_358_tx : 1;
+	unsigned can_0x358_ADC_358_rx : 1;
+	unsigned can_0x36e_ECU_36E_status : 2;
+	unsigned can_0x36e_ECU_36E_tx : 1;
+	unsigned can_0x36e_ECU_36E_rx : 1;
+	unsigned can_0x3aa_ADC_3AA_status : 2;
+	unsigned can_0x3aa_ADC_3AA_tx : 1;
+	unsigned can_0x3aa_ADC_3AA_rx : 1;
+	can_0x144_ECU_144_t can_0x144_ECU_144;
+	can_0x147_ADC_147_t can_0x147_ADC_147;
+	can_0x14a_ADC_14A_t can_0x14a_ADC_14A;
+	can_0x24b_ECU_24B_t can_0x24b_ECU_24B;
+	can_0x250_ADC_250_t can_0x250_ADC_250;
+	can_0x358_ADC_358_t can_0x358_ADC_358;
+	can_0x36e_ECU_36E_t can_0x36e_ECU_36E;
+	can_0x3aa_ADC_3AA_t can_0x3aa_ADC_3AA;
+} POSTPACK can_obj_bcan_dbc_h_t;
+
+int unpack_message(can_obj_bcan_dbc_h_t *o, const unsigned long id, uint64_t data, uint8_t dlc, dbcc_time_stamp_t time_stamp);
+int pack_message(can_obj_bcan_dbc_h_t *o, const unsigned long id, uint64_t *data);
+int print_message(const can_obj_bcan_dbc_h_t *o, const unsigned long id, FILE *output);
+
+int decode_can_0x144_ACC_LatAngReq(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x144_ACC_LatAngReq(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x144_ACC_MotorTorqueMaxLimitRequest(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x144_ACC_MotorTorqueMaxLimitRequest(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x144_ACC_MotorTorqueMinLimitRequest(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x144_ACC_MotorTorqueMinLimitRequest(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x144_ADS_Reqmode(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x144_ADS_Reqmode(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x144_ACC_ADCReqType(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x144_ACC_ADCReqType(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x144_ACC_LatAngReqActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x144_ACC_LatAngReqActive(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x147_EpsSasSteerAg(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x147_EpsSasSteerAg(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x147_EPS_Pinionang(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x147_EPS_Pinionang(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x147_EspVehSpd(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x147_EspVehSpd(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x147_EpsSteerAgRate(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x147_EpsSteerAgRate(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x147_EPS_ADS_Abortfeedback(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x147_EPS_ADS_Abortfeedback(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x147_EPS_LatCtrlAvailabilityStatus(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x147_EPS_LatCtrlAvailabilityStatus(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x147_EpsSasSteerAgVld(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x147_EpsSasSteerAgVld(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x147_EPS_LatCtrlActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x147_EPS_LatCtrlActive(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x147_EspVehSpdVld(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x147_EspVehSpdVld(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x14a_VcuPtTqLimMax(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x14a_VcuPtTqLimMax(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x14a_VcuPtTqLimMin(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x14a_VcuPtTqLimMin(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x14a_VcuPtTqReal(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x14a_VcuPtTqReal(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x14a_VcuShiftLvlPosn(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x14a_VcuShiftLvlPosn(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x14a_IBCU_ReduceFuncAvail(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x14a_IBCU_ReduceFuncAvail(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x14a_IBCU_FullFuncAvail(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x14a_IBCU_FullFuncAvail(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x14a_ESP_BrakeForce(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x14a_ESP_BrakeForce(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x24b_ACC_AEBTargetDeceleration(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x24b_ACC_AEBTargetDeceleration(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x24b_ACC_AccTrqReq(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x24b_ACC_AccTrqReq(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x24b_ACC_ACCTargetAcceleration(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x24b_ACC_ACCTargetAcceleration(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x24b_ACC_ACCMode(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_ACCMode(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ADCReqMode(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ADCReqMode(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ACC_AccTrqReqActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_AccTrqReqActive(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ACC_AEBVehilceHoldReq(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_AEBVehilceHoldReq(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ACC_AEBActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_AEBActive(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ACC_Driveoff_Request(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_Driveoff_Request(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ACC_DecToStop(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_DecToStop(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x24b_ACC_CDDActive(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x24b_ACC_CDDActive(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x250_ESP_YawRate(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x250_ESP_YawRate(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x250_ESP_LongAccel(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x250_ESP_LongAccel(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x250_ESP_LatAccel(const can_obj_bcan_dbc_h_t *o, double *out);
+int encode_can_0x250_ESP_LatAccel(can_obj_bcan_dbc_h_t *o, double in);
+int decode_can_0x250_EPS_ADS_ControlFeedback(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x250_EPS_ADS_ControlFeedback(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x250_ESP_YawRateValid(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x250_ESP_YawRateValid(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x250_ESP_LongAccelValid(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x250_ESP_LongAccelValid(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x250_ESP_LatAccelValid(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x250_ESP_LatAccelValid(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x358_ADS_UDLCTurnLightReq(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x358_ADS_UDLCTurnLightReq(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x36e_ADS_UDLCTurnLightReq(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x36e_ADS_UDLCTurnLightReq(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+int decode_can_0x3aa_VcuCrsSetSwtSts(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x3aa_VcuCrsSetSwtSts(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x3aa_VcuCrsResuSwtSts(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x3aa_VcuCrsResuSwtSts(can_obj_bcan_dbc_h_t *o, uint8_t in);
+int decode_can_0x3aa_VcuCrsDstSwtPlusSts(const can_obj_bcan_dbc_h_t *o, uint8_t *out);
+int encode_can_0x3aa_VcuCrsDstSwtPlusSts(can_obj_bcan_dbc_h_t *o, uint8_t in);
+
+
+#ifdef __cplusplus
+} 
+#endif
+
+#endif

+ 51 - 0
src/controller/controller_changan_shenlan_v2/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_changan_shenlan_v2/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 +=

+ 488 - 0
src/controller/controller_changan_shenlan_v2/control/control_status.cpp

@@ -0,0 +1,488 @@
+#include <control/control_status.h>
+#include <QDebug>
+
+
+
+
+
+//#if 1
+
+
+void iv::control::ControlStatus::set_cmd_checksum(unsigned char cmd_id)
+{
+    unsigned int check_sum=0;
+    if(cmd_id==0x10)
+    {
+        for(int i=0;i<7;i++)
+        {
+            check_sum^=(ServiceControlStatus.command10.byte[i]);
+        }
+        ServiceControlStatus.command10.byte[7]=check_sum;
+    }else if(cmd_id==0x11)
+    {
+        for(int i=0;i<7;i++)
+        {
+            check_sum^=(ServiceControlStatus.command11.byte[i]);
+        }
+        ServiceControlStatus.command11.byte[7]=check_sum;
+    }else if(cmd_id==0x12)
+    {
+        for(int i=0;i<7;i++)
+        {
+            check_sum^=(ServiceControlStatus.command12.byte[i]);
+        }
+        ServiceControlStatus.command12.byte[7]=check_sum;
+    }
+}
+
+
+
+
+void iv::control::ControlStatus::set_wheel_angle(float angle)
+{
+
+    int ang =(angle+870)*10;
+    ServiceControlStatus.command12.bit.ang_H = (ang)  /256;
+    ServiceControlStatus.command12.bit.ang_L = (ang)  % 256;
+}
+
+
+
+void iv::control::ControlStatus::set_wheel_speed(float speed)
+{
+
+    int angSpeed =speed;
+    ServiceControlStatus.command12.bit.ang_speed = angSpeed;
+}
+
+void iv::control::ControlStatus::set_wheel_enable(bool enable)
+{
+
+    if(enable){
+        ServiceControlStatus.command12.bit.ang_enable = 1;
+    }else{
+        ServiceControlStatus.command12.bit.ang_enable = 0;
+    }
+}
+
+
+
+
+ void iv::control::ControlStatus::set_speed_limit(float speed)
+ {
+     ServiceControlStatus.command11.bit.speed_limit = (unsigned)speed;
+ }
+
+
+
+void iv::control::ControlStatus::set_aeb(float aeb)
+{
+    int aebBrake =(aeb+16)/0.000488;
+    ServiceControlStatus.command11.bit.aeb_H = (aebBrake)  /256;
+    ServiceControlStatus.command11.bit.aeb_L = (aebBrake)  % 256;
+}
+
+void iv::control::ControlStatus::set_torque(float troque)
+{
+    command11.bit.torque=(unsigned)(troque*2.5);
+}
+
+void iv::control::ControlStatus::set_brake(float brake)
+{
+    command11.bit.brake=(unsigned)brake;
+}
+
+
+
+void iv::control::ControlStatus::set_gear(int gear)
+{
+    command11.bit.gear = (unsigned)gear;
+}
+
+void iv::control::ControlStatus::set_handBrake(bool handbrake)
+{
+    if(handbrake){
+        command11.bit.park = 2;
+    }else{
+        command11.bit.park = 1;
+    }
+}
+
+void iv::control::ControlStatus::set_driveMode(char driveMode)
+{
+    command11.bit.driveMode = (unsigned)driveMode;
+}
+
+void iv::control::ControlStatus::set_gear_enable(bool enable){
+    if (enable == true)
+        command11.bit.gear_enable = 1;
+    else
+        command11.bit.gear_enable = 0;
+}
+
+void iv::control::ControlStatus::set_acc_enable(bool enable){
+    if (enable == true)
+        command11.bit.acc_enable = 1;
+    else
+        command11.bit.acc_enable = 0;
+}
+
+void iv::control::ControlStatus::set_aeb_enable(bool enable){
+    if (enable == true)
+        command11.bit.aeb_enable = 1;
+    else
+        command11.bit.aeb_enable = 0;
+}
+
+
+//void iv::control::ControlStatus::set_win_lf(char para)
+//{
+//    command10.bit.windowlf = (unsigned)para;
+//}
+
+//void iv::control::ControlStatus::set_win_rf(char para)
+//{
+//    command10.bit.windowrf = (unsigned)para;
+//}
+
+//void iv::control::ControlStatus::set_win_lr(char para)
+//{
+//    command10.bit.windowlr = (unsigned)para;
+//}
+
+//void iv::control::ControlStatus::set_win_rr(char para)
+//{
+//    command10.bit.windowrr = (unsigned)para;
+//}
+
+//空调控制
+void iv::control::ControlStatus::set_air_on(char para)
+{
+    command10.bit.air_on = (unsigned)para;
+}
+
+
+
+//void iv::control::ControlStatus::set_air_cricle(char para)
+//{
+//    command10.bit.air_cricle = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_auto(char para)
+//{
+//    command10.bit.air_auto = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_off(char para)
+//{
+//    command10.bit.air_off = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_temup(char para)
+//{
+//    command10.bit.tem_up = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_temdown(char para)
+//{
+//    command10.bit.tem_down = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_powerup(char para)
+//{
+//    command10.bit.power_up = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_powerdown(char para)
+//{
+//    command10.bit.power_down = (unsigned)para;
+//}
+
+
+void iv::control::ControlStatus::set_obligate(char para)
+{
+    command10.bit.ignition = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_door(char enable)
+{
+    command10.bit.door = (unsigned)enable;
+}
+
+
+void iv::control::ControlStatus::set_turnsignals_control(bool left, bool right)
+{
+    if ( (left == true) && (right == false) )
+    {
+        command10.bit.turn_light = 0x01;
+    }
+    else if ( (left == false) && (right == true) )
+    {
+        command10.bit.turn_light = 0x02;
+    }
+    else if ((left == false) && (right == false))
+    {
+        command10.bit.turn_light = 0x00;
+    }
+    else
+    {
+        command10.bit.turn_light = 0x03;
+    }
+}
+
+
+void iv::control::ControlStatus::set_small_light(char para)
+{
+    command10.bit.small_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_near_light(char para)
+{
+    command10.bit.near_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_horn(char para)
+{
+    command10.bit.horn = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_far_light(char para)
+{
+    command10.bit.far_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_frog_light(char para)
+{
+    command10.bit.fog_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_wiper(char para)
+{
+    command10.bit.wiper = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_brake_light(char para)
+{
+    command10.bit.brake_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_defrog(char para)
+{
+    command10.bit.defrog = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_reverse_light(char para)
+{
+    command10.bit.revers_light = (unsigned)para;
+}
+
+
+void set_air_temp(char para);
+void set_air_mode(char para);
+void set_air_enable(bool enable);
+void set_wind_level(char para);
+void set_roof_light(char para);
+void set_home_light(char para);
+void set_air_worktime(char para);
+void set_air_offtime(char para);
+
+void iv::control::ControlStatus::set_air_temp(char para)
+{
+    command10.bit.air_temp = (unsigned)para+40;
+}
+
+
+void iv::control::ControlStatus::set_air_mode(char para)
+{
+    command10.bit.air_mode = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_air_enable(bool enable)
+{
+    if(enable){
+        command10.bit.air_enable = 0x01;
+    }else{
+        command10.bit.air_enable = 0x00;
+    }
+}
+
+void iv::control::ControlStatus::set_wind_level(char para)
+{
+    command10.bit.air_wind_level = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_roof_light(char para)
+{
+    command10.bit.roof_light = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_home_light(char para)
+{
+    command10.bit.home_light = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_air_worktime(char para)
+{
+    command10.bit.air_work_time = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_air_offtime(char para)
+{
+    command10.bit.air_off_time = (unsigned)para;
+}
+
+
+//void iv::control::ControlStatus::set_speaker(bool enable){
+//    if (enable == true)
+//        command.bit.speaker = 1;
+//    else
+//        command.bit.speaker = 0;
+//}
+
+//void iv::control::ControlStatus::set_door(char enable){
+//    if (enable == true)
+//        command.bit.door = 1;
+//    else
+//        command.bit.door = 0;
+//}
+
+//void iv::control::ControlStatus::set_doorEnable(bool enable){
+//    if (enable == true){
+//        command.bit.doorEnable = 1;
+//        command.bit.door=1;
+//    }
+//    else{
+//        command.bit.doorEnable = 0;
+//        command.bit.door=0;
+//    }
+//}
+
+////void iv::control::ControlStatus::set_flicker(bool enable){
+////    if (enable == true)
+////        command.bit.flicker = 1;
+////    else
+////        command.bit.flicker = 0;
+////}
+//void iv::control::ControlStatus::set_light(bool enable){
+//    if (enable == true)
+//       command.bit.bright = 1;
+//    else
+//       command.bit.bright = 0;
+//}
+
+//void iv::control::ControlStatus::set_leftlight(bool enable){
+//    if (enable == true)
+//       command.bit.left_turn = 1;
+//    else
+//       command.bit.left_turn = 0;
+//}
+
+
+//void iv::control::ControlStatus::set_rightlight(bool enable){
+//    if (enable == true)
+//       command.bit.right_turn = 1;
+//    else
+//       command.bit.right_turn = 0;
+//}
+
+
+
+
+
+
+//void iv::control::ControlStatus::set_turnsignals_control(bool left, bool right){
+//    if (left == true)
+//    {
+//        command.bit.left_turn = 1;
+//        command.bit.right_turn = 0;
+//    }
+//    else if (right == true)
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 1;
+//    }
+//    else
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 0;
+//    }
+//}
+
+
+
+
+
+
+
+
+//#else
+
+//void iv::control::ControlStatus::set_accelerate(float percent)
+//{
+//    command.bit.acce = (unsigned)((percent + 7) * 20);
+//}
+//void iv::control::ControlStatus::set_wheel_angle(float angle)
+//{
+//    command.bit.ang_H = angle * 10 >> 8;
+
+//    command.bit.ang_L = angle * 10 % 256;
+//}
+//void iv::control::ControlStatus::set_engine(char enable)
+//{
+//    command.bit.engine = enable;
+//}
+//void iv::control::ControlStatus::set_door(char enable){
+//    command.bit.door = enable;
+//}
+//void iv::control::ControlStatus::set_speaker(bool enable){
+//    if (enable == true)
+//        command.bit.speaker = 1;
+//    else
+//        command.bit.speaker = 0;
+//}
+//void iv::control::ControlStatus::set_flicker(bool enable){
+//    if (enable == true)
+//        command.bit.flicker = 1;
+//    else
+//        command.bit.flicker = 0;
+//}
+//void iv::control::ControlStatus::set_light(bool enable){
+//    if (enable == true)
+//       command.bit.bright = 1;
+//    else
+//       command.bit.bright = 0;
+//}
+//void iv::control::ControlStatus::set_turnsignals_control(bool left, bool right){
+//    if (left == true)
+//    {
+//        command.bit.left_turn = 1;
+//        command.bit.right_turn = 0;
+//    }
+//    else if (right == true)
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 1;
+//    }
+//    else
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 0;
+//    }
+//}
+//#endif

+ 108 - 0
src/controller/controller_changan_shenlan_v2/control/control_status.h

@@ -0,0 +1,108 @@
+#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:
+    /*****************
+             * ****测试标志位*****
+             * ***************/
+    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;
+
+    Command10 command10 ;
+    Command11 command11 ;
+    Command12 command12;
+    Command_Response command_reponse;
+
+    int command_ID10 = 0x10;
+    int command_ID11 = 0x11;
+    int command_ID12 = 0x12;
+
+
+    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_gear(int gear);
+    void set_handBrake(bool handBrake);
+    void set_driveMode(char mode);
+    void set_gear_enable(bool enable);
+    void set_aeb_enable(bool enable);
+    void set_acc_enable(bool enable);
+
+
+
+
+    void set_win_lf(char para);
+    void set_win_rf(char para);
+    void set_win_lr(char para);
+    void set_win_rr(char para);
+    void set_air_on(char para);
+    void set_air_cricle(char para);
+    void set_air_auto(char para);
+    void set_air_off(char para);
+    void set_air_temup(char para);
+    void set_air_temdown(char para);
+    void set_air_powerup(char para);
+    void set_air_powerdown(char para);
+    void set_obligate(char para);
+    void set_door(char enable);
+    void set_turnsignals_control(bool left, bool right);
+    void set_small_light(char para);
+    void set_near_light(char para);
+    void set_horn(char para);
+    void set_far_light(char para);
+    void set_frog_light(char para);
+    void set_wiper(char para);
+    void set_brake_light(char para);
+    void set_defrog(char para);
+    void set_reverse_light(char para);
+
+    void set_air_temp(char para);
+    void set_air_mode(char para);
+    void set_air_enable(bool enable);
+    void set_wind_level(char para);
+    void set_roof_light(char para);
+    void set_home_light(char para);
+    void set_air_worktime(char para);
+    void set_air_offtime(char para);
+
+    void set_cmd_checksum(unsigned char cmd_id);
+
+
+
+
+
+
+};
+typedef boost::serialization::singleton<iv::control::ControlStatus> ControlStatusSingleton;
+}
+}
+#define ServiceControlStatus iv::control::ControlStatusSingleton::get_mutable_instance()

+ 145 - 0
src/controller/controller_changan_shenlan_v2/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

+ 204 - 0
src/controller/controller_changan_shenlan_v2/control/controller.cpp

@@ -0,0 +1,204 @@
+#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(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_mode(char mode){
+    ServiceControlStatus.set_driveMode(mode);
+}
+//车窗控制
+//void iv::control::Controller::control_win_lf(char para){
+//     ServiceControlStatus.set_win_lf(para);
+//}
+//void iv::control::Controller::control_win_rf(char para){
+//     ServiceControlStatus.set_win_rf(para);
+//}
+
+//void iv::control::Controller::control_win_lr(char para){
+//     ServiceControlStatus.set_win_lr(para);
+//}
+
+//void iv::control::Controller::control_win_rr(char para){
+//     ServiceControlStatus.set_win_rr(para);
+//}
+
+//空调控制
+void iv::control::Controller::control_air_on(bool enable){
+    if(enable){
+        ServiceControlStatus.set_air_on(1);
+    }else{
+        ServiceControlStatus.set_air_on(0);
+    }
+}
+//void iv::control::Controller::control_air_cricle(char para){
+//     ServiceControlStatus.set_air_cricle(para);
+//}
+//void iv::control::Controller::control_air_auto(char para){
+//     ServiceControlStatus.set_air_auto(para);
+//}
+//void iv::control::Controller::control_air_off(char para){
+//     ServiceControlStatus.set_air_off(para);
+//}
+//void iv::control::Controller::control_air_temup(char para){
+//     ServiceControlStatus.set_air_temup(para);
+//}
+//void iv::control::Controller::control_air_temdown(char para){
+//     ServiceControlStatus.set_air_temdown(para);
+//}
+//void iv::control::Controller::control_air_powerup(char para){
+//     ServiceControlStatus.set_air_powerup(para);
+//}
+//void iv::control::Controller::control_air_powerdown(char para){
+//     ServiceControlStatus.set_air_powerdown(para);
+//}
+//点火控制
+void iv::control::Controller::control_obligate(char para){
+    ServiceControlStatus.set_obligate(para);
+}
+//车门控制
+void iv::control::Controller::control_door(char enable){
+    ServiceControlStatus.set_door(enable);
+}
+//车灯控制
+void iv::control::Controller::control_turnsignals(bool left, bool right){
+    ServiceControlStatus.set_turnsignals_control(left,right);
+}
+void iv::control::Controller::control_small_light(char para){
+    ServiceControlStatus.set_small_light(para);
+}
+void iv::control::Controller::control_near_light(char para){
+    ServiceControlStatus.set_near_light(para);
+}
+
+void iv::control::Controller::control_far_light(char para){
+    ServiceControlStatus.set_far_light(para);
+}
+void iv::control::Controller::control_frog_light(char para){
+    ServiceControlStatus.set_frog_light(para);
+}
+void iv::control::Controller::control_brake_light(char para){
+    ServiceControlStatus.set_brake_light(para);
+}
+void iv::control::Controller::control_defrog(char para){
+    ServiceControlStatus.set_defrog(para);
+}
+void iv::control::Controller::control_reverse_light(char para){
+    ServiceControlStatus.set_reverse_light(para);
+}
+
+//喇叭控制
+void iv::control::Controller::control_horn(char para){
+    ServiceControlStatus.set_horn(para);
+}
+//雨刷控制
+void iv::control::Controller::control_wiper(char para){
+    ServiceControlStatus.set_wiper(para);
+}
+
+
+void iv::control::Controller::control_air_temp(char para){
+    ServiceControlStatus.set_air_temp(para);
+}
+
+void iv::control::Controller::control_air_mode(char para){
+    ServiceControlStatus.set_air_mode(para);
+}
+
+void iv::control::Controller::control_air_enable(bool enable){
+    ServiceControlStatus.set_air_enable(enable);
+}
+
+void iv::control::Controller::control_wind_level(char para){
+    ServiceControlStatus.set_wind_level(para);
+}
+
+void iv::control::Controller::control_roof_light(char para){
+    ServiceControlStatus.set_roof_light(para);
+}
+
+void iv::control::Controller::control_home_light(char para){
+    ServiceControlStatus.set_home_light(para);
+}
+
+void iv::control::Controller::control_air_worktime(char para){
+    ServiceControlStatus.set_air_worktime(para);
+}
+
+void iv::control::Controller::control_air_offtime(char para){
+    ServiceControlStatus.set_air_offtime(para);
+}
+
+
+
+
+
+//void iv::control::Controller::control_flicker(bool enable){
+//    ServiceControlStatus.set_flicker(enable);
+//}
+//void iv::control::Controller::control_braking(float percent){
+
+//}

+ 83 - 0
src/controller/controller_changan_shenlan_v2/control/controller.h

@@ -0,0 +1,83 @@
+#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(float brake);
+            void control_gear(float gear);
+            void control_handBrake(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 control_win_lf(char para);
+            void control_win_rf(char para);
+            void control_win_lr(char para);
+            void control_win_rr(char para);
+            void control_air_on(bool enable);
+            void control_air_cricle(char para);
+            void control_air_auto(char para);
+            void control_air_off(char para);
+            void control_air_temup(char para);
+            void control_air_temdown(char para);
+            void control_air_powerup(char para);
+            void control_air_powerdown(char para);
+            void control_obligate(char para);
+            void control_door(char enable);
+            void control_turnsignals(bool left, bool right);
+            void control_small_light(char para);
+            void control_near_light(char para);
+            void control_horn(char para);
+            void control_far_light(char para);
+            void control_frog_light(char para);
+            void control_wiper(char para);
+            void control_brake_light(char para);
+            void control_defrog(char para);
+            void control_reverse_light(char para);
+            void cmd_checksum(unsigned char cmd_id);
+
+
+
+            void control_air_temp(char para);
+            void control_air_mode(char para);
+            void control_air_enable(bool enable);
+            void control_wind_level(char para);
+            void control_roof_light(char para);
+            void control_home_light(char para);
+            void control_air_worktime(char para);
+            void control_air_offtime(char para);
+
+            ///* 获取当前车辆状态*/
+            //void getCurrentCarStatus(iv::CarStatus & car_status);
+
+        private:
+        };
+    }
+}
+
+#endif // !_IV_CONTROL_CONTROLLER_

+ 114 - 0
src/controller/controller_changan_shenlan_v2/control/vv7.h

@@ -0,0 +1,114 @@
+#pragma once
+
+#if 1
+struct Command_Bit10
+{
+    unsigned char air_temp ;
+    unsigned char air_mode : 3;
+    unsigned char air_enable : 1;
+    unsigned char air_wind_level : 3;
+    unsigned char air_reserved : 1;
+    unsigned char ignition : 2;
+    unsigned char door : 2;
+    unsigned char Reserved :2;
+    unsigned char air_on : 2;
+    unsigned char turn_light : 2;
+    unsigned char small_light : 1;
+    unsigned char near_light : 1;
+    unsigned char horn : 1;
+    unsigned char far_light : 1;
+    unsigned char fog_light : 1;
+    unsigned char wiper : 1;
+    unsigned char brake_light : 1;
+    unsigned char defrog : 1;
+    unsigned char revers_light : 1;
+    unsigned char roof_light : 1;
+    unsigned char home_light : 1;
+    unsigned char Reserved0 :3;
+    unsigned char air_work_time;
+    unsigned char  air_off_time;
+    unsigned char  checkSum;
+};
+
+
+union Command10
+{
+    Command_Bit10 bit;
+    unsigned char byte[8];
+};
+
+
+struct Command_Bit11
+{
+    unsigned char speed_limit;
+    unsigned char  aeb_H;
+    unsigned char  aeb_L;
+    unsigned char torque;
+    unsigned char brake;
+    unsigned char gear:3;
+    unsigned char Reserved :1;
+    unsigned char park :2;
+    unsigned char Reserved0 :2;
+    unsigned char Reserved1 :2;
+    unsigned char Reserved2 :2;
+    unsigned char driveMode :1;
+    unsigned char gear_enable :1;
+    unsigned char aeb_enable :1;
+    unsigned char acc_enable :1;
+    unsigned char checkSum;
+};
+
+
+
+
+union Command11
+{
+    Command_Bit11 bit;
+    unsigned char byte[8];
+};
+
+
+struct Command_Bit12
+{
+    unsigned char ang_speed;
+    unsigned char  ang_H;
+    unsigned char  ang_L;
+    unsigned char reserved0;
+    unsigned char reserved1;
+    unsigned char reserved2;
+    unsigned char Reserved : 6;
+    unsigned char ang_enable : 1;
+    unsigned char Reserved0 : 1;
+    unsigned char checkSum;
+};
+
+
+union Command12
+{
+    Command_Bit12 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];
+};
+
+#else
+
+#endif
+
+
+

+ 52 - 0
src/controller/controller_changan_shenlan_v2/controller_changan_shenlan_v2.pro

@@ -0,0 +1,52 @@
+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($$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/.
+
+
+
+LIBS += -livprotoif

+ 593 - 0
src/controller/controller_changan_shenlan_v2/main.cpp

@@ -0,0 +1,593 @@
+#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;
+
+static bool gbHaveVehSpd = false;
+static double gfVehSpd = 0.0;
+
+boost::shared_ptr<iv::control::Controller> gcontroller;	//实际车辆控制器
+
+static QMutex gMutex;
+
+
+// signal: @ACC_LatAngReq    //更改CANid
+#define ECU_1C4_ACC_LatAngReq_CovFactor (0.1)
+// conversion value to CAN signal
+#define ECU_1C4_ACC_LatAngReq_toS(x) ((int16_t)((x) / 0.1 + 7200))
+
+// signal: @ACC_MotorTorqueMaxLimitRequest
+#define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_CovFactor (0.02)
+// conversion value to CAN signal
+#define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
+
+// signal: @ACC_MotorTorqueMinLimitRequest
+#define ECU_1C4_ACC_MotorTorqueMinLimitRequest_CovFactor (0.02)
+// conversion value to CAN signal
+#define ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
+
+typedef struct
+{
+    int16_t ACC_LatAngReq;
+    //uint8_t ADS_Reqmode;  //20221102, 新车没有此信号
+    int16_t ACC_MotorTorqueMaxLimitRequest;
+    uint8_t ACC_LatAngReqActive;
+    int16_t ACC_MotorTorqueMinLimitRequest;
+    //uint8_t ACC_ADCReqType; //20221102, 新车没有此信号
+} ECU_1C4_t;
+
+// signal: @ACC_AccTrqReq
+#define ECU_24E_ACC_AccTrqReq_CovFactor (1)
+// conversion value to CAN signal
+#define ECU_24E_ACC_AccTrqReq_toS(x) ((int16_t)((x) + 16384))
+
+// signal: @ACC_ACCTargetAcceleration
+#define ECU_24E_ACC_ACCTargetAcceleration_CovFactor (0.05)
+// conversion value to CAN signal
+#define ECU_24E_ACC_ACCTargetAcceleration_toS(x) ((int16_t)((x) / 0.05 + 200))
+
+// signal: @ACC_AEBTargetDeceleration
+#define ECU_24E_ACC_AEBTargetDeceleration_CovFactor (0.0005)
+// conversion value to CAN signal
+#define ECU_24E_ACC_AEBTargetDeceleration_toS(x) ((int32_t)((x) / 0.0005 + 32000))
+
+typedef struct
+{
+    int16_t ACC_AccTrqReq;
+    uint8_t ACC_AccTrqReqActive;
+    int16_t ACC_ACCTargetAcceleration;
+    int32_t ACC_AEBTargetDeceleration;
+    uint8_t ACC_AEBVehilceHoldReq;
+    uint8_t ADCReqMode;
+    uint8_t ACC_AEBActive;
+    uint8_t ACC_Driveoff_Request;
+    uint8_t ACC_DecToStop;
+    uint8_t ACC_CDDActive;
+    uint8_t ACC_ACCMode;
+} ECU_24E_t;
+
+typedef struct
+{
+    uint8_t ADS_UDLCTurnLightReq;
+} ECU_36E_t;
+
+unsigned char byte_1C4[64];//byte_144[8];
+unsigned char byte_24E[64];
+unsigned char byte_36E[64];
+
+ECU_1C4_t _m1C4 = {0,0,0,0};
+ECU_24E_t _m24E = {0,0,0,0,0,0,0,0,0,0,0};
+ECU_36E_t _m36E = {0};
+
+void ExecSend();
+
+void executeDecition(const iv::brain::decition &decition)
+{
+
+    static int xieya = 50;
+//     std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
+//     std::cout<<"angle_mode is "<<decition.angle_mode()<<" angle_active is "<<decition.angle_active()<<std::endl;
+//     std::cout<<"brake_type is "<<decition.brake_type()<<" acc_active is "<<decition.acc_active()<<std::endl;
+//     std::cout<<"brake is "<<decition.brake()<<" brake_active is "<<decition.brake_active()<<std::endl;
+//     std::cout<<"auto_mode is "<<decition.auto_mode()<<" rightlamp is "<<decition.rightlamp()<<std::endl;
+    _m1C4.ACC_LatAngReq = ECU_1C4_ACC_LatAngReq_toS(decition.wheelangle());
+    //_m1C4.ADS_Reqmode = decition.angle_mode(); //20221102,新车没有此信号
+    _m1C4.ACC_MotorTorqueMaxLimitRequest = ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(10);
+    _m1C4.ACC_LatAngReqActive = decition.angle_active();
+    _m1C4.ACC_MotorTorqueMinLimitRequest = ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(-10);
+//    _m144.ACC_ADCReqType = decition.brake_type();//ADC请求类型(制动时为1,其余情况为0)
+    if(decition.brake()>(-0.0000001))
+    {
+        //_m144.ACC_ADCReqType = 0;//ADC请求类型(制动时为1,其余情况为0)//20221102,新车没有此信号
+       // _m24B.ADCReqMode = 0;//20221102,新车没有此信号
+        _m24E.ACC_DecToStop =0;
+    }
+    else
+    {
+        //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
+       // _m24B.ADCReqMode = 1;//20221102,新车没有此信号
+         _m24E.ACC_DecToStop =1;
+    }
+
+//    std::cout<<" type: "<<(int)_m144.ACC_ADCReqType<<std::endl;
+
+
+    /*制动过程用的减速度,加速用扭矩*/
+    _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(decition.torque());
+    _m24E.ACC_AccTrqReqActive = decition.acc_active();
+    if(decition.brake()<(-0.5))
+    {
+        _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(-0.5);
+    }
+    else
+        _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(decition.brake());
+
+
+ //   std::cout<<" brake : "<<decition.brake()<<std::endl;
+ //   std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
+    if(decition.brake()>(-0.0000001))
+    {
+
+        if(xieya > 0)
+        {
+            _m24E.ACC_CDDActive = 1;
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
+            _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(0);
+            _m24E.ACC_Driveoff_Request = 1;
+
+            //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
+            //_m24B.ADCReqMode = 1;   //20221102,新车没有此信号
+             _m24E.ACC_DecToStop =1;
+            xieya--;
+            std::cout<<" xieya. now veh speed: "<<gfVehSpd<<std::endl;
+        }
+        else
+        {
+            _m24E.ACC_CDDActive = 0;
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
+            _m24E.ACC_Driveoff_Request = 0;
+        }
+    }
+    else
+    {
+        _m24E.ACC_CDDActive = 1;
+
+        _m24E.ACC_Driveoff_Request = 0;
+
+
+    }
+ //       _m24B.ACC_CDDActive = decition.brake_active();
+
+
+
+//    std::cout<<" req mode: "<<_m144.ADS_Reqmode<<std::endl;
+    //byte_144[0] = ((_m144.ACC_LatAngReq >> 9) & (0x1FU)) | ((_m144.ADS_Reqmode & (0x07U)) << 5);
+ //   qDebug(" req mode: %d byte: %02X  ",_m144.ADS_Reqmode, byte_144[0]);
+   // byte_144[1] = ((_m144.ACC_LatAngReq >> 1) & (0xFFU));
+    //byte_144[2] = ((_m144.ACC_LatAngReq & (0x01U)) << 7) | ((_m144.ACC_MotorTorqueMaxLimitRequest >> 5) & (0x3FU)) | ((_m144.ACC_LatAngReqActive & (0x01U)) << 6);
+    //byte_144[3] = ((_m144.ACC_MotorTorqueMaxLimitRequest & (0x1FU)) << 3) | ((_m144.ACC_MotorTorqueMinLimitRequest >> 8) & (0x07U));
+    //byte_144[4] = (_m144.ACC_MotorTorqueMinLimitRequest & (0xFFU));
+    //byte_144[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
+
+
+    byte_1C4[0] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest >> 3) & (0xFFU));
+ //   qDebug(" req mode: %d byte: %02X  ",_m144.ADS_Reqmode, byte_144[0]);
+    byte_1C4[1] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest & (0x07U)) << 5) | ((_m1C4.ACC_MotorTorqueMinLimitRequest >> 6) & (0x1FU));
+    byte_1C4[2] = ((_m1C4.ACC_MotorTorqueMinLimitRequest & (0x3FU)) << 2) | ((_m1C4.ACC_LatAngReq >> 12) & (0x03U));
+    byte_1C4[3] = (((_m1C4.ACC_LatAngReq>>4 )& (0xFFU)));
+    byte_1C4[4] = ((_m1C4.ACC_LatAngReq & (0x0FU))<<4)|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
+    //byte_1C4[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
+
+    //    _m24B.ACC_AEBTargetDeceleration = 0;
+    //    _m24B.ACC_AEBVehilceHoldReq = 0;
+    //    _m24B.ADCReqMode = 0;
+    //    _m24B.ACC_AEBActive = 0;
+    //    _m24B.ACC_Driveoff_Request = 0;
+    //    _m24B.ACC_DecToStop = 0;
+//    std::cout<<" brake : "<<decition.brake()<<std::endl;
+//    std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
+    if(decition.brake()>(-0.0000001))
+    {
+        _m24E.ACC_CDDActive = 0;
+        _m24E.ACC_Driveoff_Request = 1;
+        if(xieya > 0)
+        {
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
+            xieya--;
+        }
+        else
+        {
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
+        }
+    }
+    else
+    {
+        _m24E.ACC_CDDActive = 1;
+
+        _m24E.ACC_Driveoff_Request = 0;
+
+        if(gbHaveVehSpd)
+        {
+            if(gfVehSpd < 0.01)
+            {
+                if(xieya != 50)std::cout<<"need xieya. "<<std::endl;
+                xieya = 50;
+
+            }
+        }
+    }
+ //       _m24B.ACC_CDDActive = decition.brake_active();
+    _m24E.ACC_ACCMode = decition.auto_mode();
+//    std::cout<<"acc mode: "<<(int)_m24B.ACC_ACCMode<<std::endl;
+
+
+   // byte_24B[0] = ((_m24B.ACC_AccTrqReq >> 7) & (0xFFU));
+    //byte_24B[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
+    //byte_24B[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
+    //byte_24B[3] = ((_m24B.ACC_ACCTargetAcceleration & (0x07U)) << 5) | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
+    //byte_24B[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
+    //byte_24B[5] = ((_m24B.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24B.ACC_AEBVehilceHoldReq & (0x01U));
+    //byte_24B[6] = ((_m24B.ADCReqMode & (0x03U)) << 1) | ((_m24B.ACC_AEBActive & (0x01U)) << 3) | ((_m24B.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24B.ACC_DecToStop & (0x01U)) << 6) | ((_m24B.ACC_CDDActive & (0x01U)) << 7);
+    //byte_24B[7] = (_m24B.ACC_ACCMode & (0x07U));
+
+
+    byte_24E[0] = ((_m24E.ACC_ACCTargetAcceleration) & (0xFFU));
+    //byte_24E[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
+    //byte_24E[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
+    byte_24E[3] = ((_m24E.ACC_DecToStop & (0x01U)) << 7);// | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
+    //byte_24E[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
+    byte_24E[5] = ((_m24E.ACC_CDDActive & (0x01U)) << 4);//((_m24E.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24E.ACC_AEBVehilceHoldReq & (0x01U));
+    byte_24E[6] = ((_m24E.ACC_Driveoff_Request & (0x01U)) << 7)|((_m24E.ACC_ACCMode & (0x07U))<<4);//((_m24E.ADCReqMode & (0x03U)) << 1) | ((_m24E.ACC_AEBActive & (0x01U)) << 3) | ((_m24E.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24E.ACC_DecToStop & (0x01U)) << 6) | ((_m24E.ACC_CDDActive & (0x01U)) << 7);
+    byte_24E[8] = ((_m24E.ACC_AEBTargetDeceleration>>8) & (0xFFU));
+    byte_24E[9] = ((_m24E.ACC_AEBTargetDeceleration) & (0xFFU));
+    byte_24E[10] = ((_m24E.ACC_AEBActive & (0x01U)) << 7);
+    byte_24E[11] = ((_m24E.ACC_AccTrqReq>>13 )& (0x03U));
+    byte_24E[12] = ((_m24E.ACC_AccTrqReq>>5 )& (0xFFU));
+    byte_24E[13] = ((_m24E.ACC_AccTrqReq & (0x1FU)<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
+
+//    if(decition.leftlamp() == true && decition.rightlamp() == false)
+//        _m36E.ADS_UDLCTurnLightReq = 3;
+//    else if(decition.leftlamp() == false && decition.rightlamp() == true)
+//        _m36E.ADS_UDLCTurnLightReq = 4;
+//    else
+//        _m36E.ADS_UDLCTurnLightReq = 0;
+
+//    byte_36E[0] = ((_m36E.ADS_UDLCTurnLightReq & (0x07U)) << 5);
+
+}
+
+void Activate()
+{
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    iv::brain::decition xdecition;
+//    for(int j=0;j<100000;j++)
+//    {
+        std::cout<<" run "<<std::endl;
+    for(int i = 0; i < 10; i++){
+        xdecition.set_wheelangle(0.0);
+        xdecition.set_angle_mode(0);
+        xdecition.set_angle_active(0);
+        xdecition.set_acc_active(0);
+        xdecition.set_brake_active(0);
+//        xdecition.set_brake_type(0);
+        xdecition.set_auto_mode(0);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    for(int i = 0; i < 10; i++){
+        xdecition.set_wheelangle(0.0);
+        xdecition.set_angle_mode(2);
+        xdecition.set_angle_active(1);
+        xdecition.set_acc_active(1);
+        xdecition.set_brake_active(1);
+//        xdecition.set_brake_type(1);
+        xdecition.set_auto_mode(3);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+//    }
+}
+
+void UnAcitvate()
+{
+    iv::brain::decition xdecition;
+    for(int i = 0; i < 10; i++){
+        xdecition.set_wheelangle(0);
+        xdecition.set_angle_mode(2);
+        xdecition.set_angle_active(1);
+        xdecition.set_acc_active(1);
+        xdecition.set_brake_active(1);
+//        xdecition.set_brake_type(1);
+        xdecition.set_auto_mode(3);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    for(int i = 0; i < 10; i++){
+        xdecition.set_wheelangle(0);
+        xdecition.set_angle_mode(0);
+        xdecition.set_angle_active(0);
+        xdecition.set_acc_active(0);
+        xdecition.set_brake_active(0);
+//        xdecition.set_brake_type(0);
+        xdecition.set_auto_mode(0);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+}
+
+void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
+{
+    (void)index;
+    (void)dt;
+    (void)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.has_epsmode())
+    {
+    if(xchassis.epsmode() == 0)
+    {
+        gbChassisEPS = true;
+    }
+    }
+
+    if(xchassis.has_vel())
+    {
+        gfVehSpd = xchassis.vel();
+        gbHaveVehSpd = true;
+  //      std::cout<<" gf Veh speed : "<<gfVehSpd<<std::endl;
+    }
+}
+
+
+void ListenDeciton(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    (void)index;
+    (void)dt;
+    (void)strmemname;
+    static qint64 oldtime = QDateTime::currentMSecsSinceEpoch();
+    iv::brain::decition xdecition;
+
+    if(!xdecition.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"ListenDecition parse error."<<std::endl;
+        return;
+    }
+
+    //    if(xdecition.gear() != 4)
+    //    {
+    //        qDebug("not D");
+    //    }
+    xdecition.set_angle_mode(2);
+    xdecition.set_angle_active(1);
+    xdecition.set_acc_active(1);
+    xdecition.set_brake_active(1);
+//    xdecition.set_brake_type(1);
+    xdecition.set_auto_mode(3);
+
+    if((oldtime - QDateTime::currentMSecsSinceEpoch())<-100)qDebug("dection time is %lld diff is %lld ",QDateTime::currentMSecsSinceEpoch(),oldtime - QDateTime::currentMSecsSinceEpoch());
+    oldtime = QDateTime::currentMSecsSinceEpoch();
+    gMutex.lock();
+    gdecition.CopyFrom(xdecition);
+    gMutex.unlock();
+    gnDecitionNum = gnDecitionNumMax;
+    gbChassisEPS = false;
+
+}
+
+void ExecSend()
+{
+    static int nCount = 0;
+    nCount++;
+    iv::can::canmsg xmsg;
+    iv::can::canraw xraw;
+    //    unsigned char * strp = (unsigned char *)&(ServiceControlStatus.command10.byte[0]);
+    //    qDebug("%02x %02x %02x %02x %02x %02x %02x %02x",strp[0],strp[1],strp[2],strp[3],strp[4],strp[5],strp[6],strp[7]);
+
+    xraw.set_id(0x1C4);
+    xraw.set_data(byte_1C4,64);
+    xraw.set_bext(false);
+    xraw.set_bremote(false);
+    xraw.set_len(64);
+    iv::can::canraw * pxraw1C4 = xmsg.add_rawmsg();
+    pxraw1C4->CopyFrom(xraw);
+//    qDebug(" 0x144: %02X %02X %02X %02X %02X %02X %02X %02X",byte_144[0],byte_144[1],byte_144[2],byte_144[3],
+//            byte_144[4],byte_144[5],byte_144[6],byte_144[7]);
+    xmsg.set_channel(0);
+    xmsg.set_index(gnIndex);
+
+    xraw.set_id(0x24E);
+    xraw.set_data(byte_24E,64);
+    xraw.set_bext(false);
+    xraw.set_bremote(false);
+    xraw.set_len(64);
+    if(nCount%2 == 1)
+    {
+        iv::can::canraw * pxraw24E = xmsg.add_rawmsg();
+        pxraw24E->CopyFrom(xraw);
+    }
+    xmsg.set_channel(0);
+    xmsg.set_index(gnIndex);
+
+//    xraw.set_id(0x36E);
+//    xraw.set_data(byte_36E,8);
+//    xraw.set_bext(false);
+//    xraw.set_bremote(false);
+//    xraw.set_len(8);
+//    if(nCount == 10)
+//    {
+//        iv::can::canraw * pxraw36E = xmsg.add_rawmsg();
+//        pxraw36E->CopyFrom(xraw);
+//        nCount = 0;
+//    }
+//    xmsg.set_channel(0);
+//    xmsg.set_index(gnIndex);
+
+    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()
+{
+    for (uint8_t i = 0; i < 64; i++) //CAN  to  canfd
+    {
+        byte_1C4[i] = 0;
+        byte_24E[i] = 0;
+        //byte_36E[i] = 0;
+    }
+}
+
+void sendthread()
+{
+    initial();
+    iv::brain::decition xdecition;
+
+    UnAcitvate();
+ //   UnAcitvate();
+
+    int nstate = 0; //0 Un 1 Activate
+//    Activate();
+    while(gbSendRun)
+    {
+        if(gnDecitionNum <= 0)
+        {
+            if(nstate == 1)
+            {
+                UnAcitvate();
+                nstate = 0;
+            }
+            xdecition.CopyFrom(gdecition_def);
+        }
+        else
+        {
+            if(nstate == 0)
+            {
+                Activate();
+                nstate = 1;
+            }
+            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_changan_shenlan");
+    QCoreApplication a(argc, argv);
+
+    QString strpath = QCoreApplication::applicationDirPath();
+
+    if(argc < 2)
+        strpath = strpath + "/controller_changan_shenlan.xml";
+    else
+        strpath = argv[1];
+    std::cout<<strpath.toStdString()<<std::endl;
+
+//    gdecition_def.set_accelerator(-0.5);
+    gdecition_def.set_brake(0);
+    gdecition_def.set_rightlamp(false);
+    gdecition_def.set_leftlamp(false);
+    gdecition_def.set_wheelangle(0);
+
+    gdecition_def.set_angle_mode(0);
+    gdecition_def.set_angle_active(0);
+    gdecition_def.set_acc_active(0);
+//    gdecition_def.set_brake_active(1);
+    gdecition_def.set_brake_type(0);
+    gdecition_def.set_auto_mode(0);
+
+//    gdecition_def.set_angle_mode(0);
+//    gdecition_def.set_angle_active(0);
+//    gdecition_def.set_acc_active(0);
+//    gdecition_def.set_brake_active(0);
+//    gdecition_def.set_brake_type(0);
+//    gdecition_def.set_auto_mode(0);
+
+    gTime.start();
+
+    gcontroller = boost::shared_ptr<iv::control::Controller>(new iv::control::Controller());
+
+    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();
+}