From d2773359cdbe633598cb79fe2cb50de32b79612e Mon Sep 17 00:00:00 2001 From: Cole Lewis Date: Mon, 20 May 2024 01:07:05 -0700 Subject: [PATCH] More CAN changes; temp not working over CAN --- bms/.mbed | 1 + bms/src/BmsConfig.h | 4 + bms/src/Can.cpp | 45 +++++-- bms/src/Can.h | 22 +++- bms/src/Main.cpp | 60 +++++---- mainCANbus.dbc | 108 ++++++++++++---- mainCANbus.dbf | 307 ++++++++++++++++++++++++++++++++++++++++++++ mainCANbus.log | 59 +++++++++ 8 files changed, 538 insertions(+), 68 deletions(-) create mode 100644 mainCANbus.dbf create mode 100644 mainCANbus.log diff --git a/bms/.mbed b/bms/.mbed index 4f9dae0..51eecf0 100644 --- a/bms/.mbed +++ b/bms/.mbed @@ -1,3 +1,4 @@ ROOT=. TARGET=NUCLEO_L432KC TARGET_CODE=0770 +TARGET_SERIAL=0671FF555185754867150637 diff --git a/bms/src/BmsConfig.h b/bms/src/BmsConfig.h index a3baf5e..e7889d9 100644 --- a/bms/src/BmsConfig.h +++ b/bms/src/BmsConfig.h @@ -91,6 +91,10 @@ extern DigitalOut* chargerControl; #ifndef CAR_POWER_PERCENT #define CAR_POWER_PERCENT 0.95 #endif +// maximum allowed current draw by the motor controller +#ifndef CAR_CURRENT_MAX +#define CAR_CURRENT_MAX 700 +#endif // percent of precharge needed to consider precharging done (and close the +AIR) #ifndef PRECHARGE_PERCENT diff --git a/bms/src/Can.cpp b/bms/src/Can.cpp index deae3fa..7ac9041 100644 --- a/bms/src/Can.cpp +++ b/bms/src/Can.cpp @@ -1,5 +1,6 @@ #include "Can.h" #include +#include CANMessage accBoardBootup() { uint8_t startupMessage[8]; @@ -20,23 +21,51 @@ CANMessage accBoardState(uint8_t glvVoltage, uint16_t tsVoltage, bool bmsFault, } CANMessage accBoardTemp(uint8_t segment, int8_t *temps) { - uint8_t data[8]; - data[0] = segment; + uint8_t data[7]; + uint32_t id; + switch (segment) { + case 0: + id = kTPDO_ACC_BOARD_Temp_0; + break; + case 1: + id = kTPDO_ACC_BOARD_Temp_1; + break; + case 2: + id = kTPDO_ACC_BOARD_Temp_2; + break; + case 3: + id = kTPDO_ACC_BOARD_Temp_3; + break; + } for (int i = 0; i < 7; i++) { - data[i+1] = (uint8_t)(temps[i]+40); + data[i] = (uint8_t)(temps[i]); } - return CANMessage(kTPDO_ACC_BOARD_Temp, data); + return CANMessage(id, data); } CANMessage accBoardVolt(uint8_t segment, uint16_t *volts) { - uint8_t data[8]; - data[0] = segment; + uint8_t data[7]; + uint32_t id; + switch (segment) { + case 0: + id = kTPDO_ACC_BOARD_Volt_0; + break; + case 1: + id = kTPDO_ACC_BOARD_Volt_1; + break; + case 2: + id = kTPDO_ACC_BOARD_Volt_2; + break; + case 3: + id = kTPDO_ACC_BOARD_Volt_3; + break; + } for (int i = 0; i < 7; i++) { - data[i+1] = (uint8_t) (50.0*volts[i]/1000.0); + data[i] = (uint8_t) (50.0*volts[i]/1000.0); } - return CANMessage(kTPDO_ACC_BOARD_Volt, data); + return CANMessage(id, data); } CANMessage motorControllerCurrentLim(uint16_t chargeCurLim, uint16_t dischargeCurLim) { diff --git a/bms/src/Can.h b/bms/src/Can.h index dcd5ea3..48dc3da 100644 --- a/bms/src/Can.h +++ b/bms/src/Can.h @@ -10,8 +10,17 @@ // SIDs From Accumulator constexpr uint32_t kTPDO_ACC_BOARD_State = 0x182; -constexpr uint32_t kTPDO_ACC_BOARD_Temp = 0x282; -constexpr uint32_t kTPDO_ACC_BOARD_Volt = 0x382; + +constexpr uint32_t kTPDO_ACC_BOARD_Temp_0 = 0x189; +constexpr uint32_t kTPDO_ACC_BOARD_Temp_1 = 0x289; +constexpr uint32_t kTPDO_ACC_BOARD_Temp_2 = 0x389; +constexpr uint32_t kTPDO_ACC_BOARD_Temp_3 = 0x489; + +constexpr uint32_t kTPDO_ACC_BOARD_Volt_0 = 0x188; +constexpr uint32_t kTPDO_ACC_BOARD_Volt_1 = 0x288; +constexpr uint32_t kTPDO_ACC_BOARD_Volt_2 = 0x388; +constexpr uint32_t kTPDO_ACC_BOARD_Volt_3 = 0x488; + constexpr uint32_t kNMT_ACC_HEARTBEAT = 0x702; constexpr uint32_t kRPDO_MAX_CURRENTS = 0x286; @@ -19,7 +28,11 @@ constexpr uint32_t kRPDO_MAX_CURRENTS = 0x286; CANMessage accBoardBootup(); /* TPDO that sends various states and information about the accumulator */ -CANMessage accBoardState(uint8_t glvVoltage, uint16_t tsVoltage, bool bmsFault, bool bmsBalancing, bool prechargeDone, bool charging, bool fansOn, bool shutdownClosed, bool unused_A, bool unused_B, uint8_t minCellVoltage, uint8_t maxCellVoltage, int16_t tsCurrent); +CANMessage accBoardState(uint8_t glvVoltage, uint16_t tsVoltage, bool bmsFault, + bool bmsBalancing, bool prechargeDone, bool charging, + bool fansOn, bool shutdownClosed, bool unused_A, + bool unused_B, uint8_t minCellVoltage, + uint8_t maxCellVoltage, int16_t tsCurrent); /* TPDO that sends all temperatures for one segment */ CANMessage accBoardTemp(uint8_t segment, int8_t *temps); @@ -28,6 +41,7 @@ CANMessage accBoardTemp(uint8_t segment, int8_t *temps); CANMessage accBoardVolt(uint8_t segment, uint16_t *voltages); /* RPDO for limiting the current to the Motor Controller (AC-X1) */ -CANMessage motorControllerCurrentLim(uint16_t chargeCurLim, uint16_t dischargeCurLim); +CANMessage motorControllerCurrentLim(uint16_t chargeCurLim, + uint16_t dischargeCurLim); #endif // _FS_BMS_SRC_CAN_H_ diff --git a/bms/src/Main.cpp b/bms/src/Main.cpp index b41bc04..bf74ca9 100644 --- a/bms/src/Main.cpp +++ b/bms/src/Main.cpp @@ -1,3 +1,4 @@ +#include #include #include #include @@ -35,7 +36,7 @@ void canCurrentLimTX(); -EventQueue queue(4*EVENTS_EVENT_SIZE); // creates an eventqueue which is thread and ISR safe. EVENTS_EVENT_SIZE is the size of the buffer allocated +EventQueue queue(32*EVENTS_EVENT_SIZE); // creates an eventqueue which is thread and ISR safe. EVENTS_EVENT_SIZE is the size of the buffer allocated @@ -66,7 +67,8 @@ bool hasFansOn = false; bool isBalancing = false; uint16_t dcBusVoltage; -uint16_t tsVoltage; +uint32_t tsVoltagemV; +//uint16_t tsVoltage; uint8_t glvVoltage; uint16_t tsCurrent; @@ -103,8 +105,8 @@ int main() { Timer t; t.start(); while (1) { - glvVoltage = glv_voltage_pin * 18530; // in mV - //printf("GLV voltage: %d mV\n", glv_voltage); + glvVoltage = (uint8_t)(glv_voltage_pin * 185.3); // in mV + //printf("GLV voltage: %d mV\n", glvVoltage * 100); while (!bmsMailbox->empty()) { BmsEvent *bmsEvent; @@ -126,16 +128,16 @@ int main() { maxCellVolt = bmsEvent->maxVolt; isBalancing = bmsEvent->isBalancing; - tsVoltage = 0; + tsVoltagemV = 0; for (int i = 0; i < BMS_BANK_COUNT*BMS_BANK_CELL_COUNT; i++) { allVoltages[i] = bmsEvent->voltageValues[i]; - tsVoltage += allVoltages[i]; + tsVoltagemV += allVoltages[i]; //printf("%d, V: %d\n", i, allVoltages[i]); } for (int i = 0; i < BMS_BANK_COUNT*BMS_BANK_TEMP_COUNT; i++) { allTemps[i] = bmsEvent->temperatureValues[i]; - //printf("%d, V: %d\n", i, allTemps[i]); + // printf("%d, T: %d\n", i, allTemps[i]); } break; @@ -173,7 +175,7 @@ int main() { } - if (dcBusVoltage >= tsVoltage * PRECHARGE_PERCENT) { + if (dcBusVoltage >= (uint16_t)(tsVoltagemV/100.0) * PRECHARGE_PERCENT) { prechargeDone = true; } @@ -205,21 +207,19 @@ void initIO() { canBus = new CAN(BMS_PIN_CAN_RX, BMS_PIN_CAN_TX, BMS_CAN_FREQUENCY); canBus->attach(canRX); - // canBus->write(accBoardBootup()); - - int canBootupUD = queue.call(&canBootupTX); + queue.call(&canBootupTX); queue.dispatch_once(); - int canBoardStateID = queue.call_every(100ms, &canBoardStateTX); - int canCurrentLimID = queue.call_every(40ms, &canCurrentLimTX); - int canVoltID0 = queue.call_every(200ms, &canVoltTX0); - int canVoltID1 = queue.call_every(200ms, &canVoltTX1); - int canVoltID2 = queue.call_every(200ms, &canVoltTX2); - int canVoltID3 = queue.call_every(200ms, &canVoltTX3); - int canTempID0 = queue.call_every(200ms, &canTempTX0); - int canTempID1 = queue.call_every(200ms, &canTempTX1); - int canTempID2 = queue.call_every(200ms, &canTempTX2); - int canTempID3 = queue.call_every(200ms, &canTempTX3); + queue.call_every(100ms, &canBoardStateTX); + queue.call_every( 40ms, &canCurrentLimTX); + queue.call_every(200ms, &canVoltTX0); + queue.call_every(200ms, &canVoltTX1); + queue.call_every(200ms, &canVoltTX2); + queue.call_every(200ms, &canVoltTX3); + queue.call_every(200ms, &canTempTX0); + queue.call_every(200ms, &canTempTX1); + queue.call_every(200ms, &canTempTX2); + queue.call_every(200ms, &canTempTX3); fan_control_pin = 0; // turn fans off at start @@ -244,7 +244,7 @@ void canBootupTX() { void canBoardStateTX() { canBus->write(accBoardState( glvVoltage, - tsVoltage, + (uint16_t)(tsVoltagemV/100.0), hasBmsFault, isBalancing, prechargeDone, @@ -257,6 +257,7 @@ void canBoardStateTX() { maxCellVolt, tsCurrent )); + ThisThread::sleep_for(1ms); } void canTempTX(uint8_t segment) { @@ -270,6 +271,7 @@ void canTempTX(uint8_t segment) { allTemps[(segment * BMS_BANK_CELL_COUNT) + 6] }; canBus->write(accBoardTemp(segment, temps)); + ThisThread::sleep_for(1ms); } void canVoltTX(uint8_t segment) { @@ -283,6 +285,14 @@ void canVoltTX(uint8_t segment) { allVoltages[(segment * BMS_BANK_CELL_COUNT) + 6] }; canBus->write(accBoardVolt(segment, volts)); + ThisThread::sleep_for(1ms); +} + +void canCurrentLimTX() { + uint16_t chargeCurrentLimit = 0x0000; + uint16_t dischargeCurrentLimit = (uint16_t)(((CAR_MAX_POWER/(tsVoltagemV/1000.0))*CAR_POWER_PERCENT < CAR_CURRENT_MAX) ? (CAR_MAX_POWER/(tsVoltagemV/1000.0)*CAR_POWER_PERCENT) : CAR_CURRENT_MAX); + canBus->write(motorControllerCurrentLim(chargeCurrentLimit, dischargeCurrentLimit)); + ThisThread::sleep_for(1ms); } void canVoltTX0() { @@ -316,9 +326,3 @@ void canTempTX2() { void canTempTX3() { canTempTX(3); } - -void canCurrentLimTX() { - uint16_t chargeCurrentLimit = 0x0000; - uint16_t dischargeCurrentLimit = (uint16_t)(CAR_MAX_POWER/117.6)*CAR_POWER_PERCENT; - canBus->write(motorControllerCurrentLim(chargeCurrentLimit, dischargeCurrentLimit)); -} \ No newline at end of file diff --git a/mainCANbus.dbc b/mainCANbus.dbc index 441da62..3980dfa 100644 --- a/mainCANbus.dbc +++ b/mainCANbus.dbc @@ -79,40 +79,40 @@ BO_ 386 TPDO_ACC_BOARD_State: 8 Vector__XXX SG_ TS_Current : 48|16@1- (0.1,0) [-3276.8|3276.7] "Amps" Vector__XXX BO_ 393 TPDO_ACC_BOARD_Temp_0: 8 Vector__XXX - SG_ Seg0_TEMP_0 : 0|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg0_TEMP_1 : 8|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg0_TEMP_2 : 16|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg0_TEMP_3 : 24|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg0_TEMP_4 : 32|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg0_TEMP_5 : 40|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg0_TEMP_6 : 48|8@1+ (1,-40) [-40|215] "" Vector__XXX + SG_ Seg0_TEMP_0 : 0|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg0_TEMP_1 : 8|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg0_TEMP_2 : 16|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg0_TEMP_3 : 24|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg0_TEMP_4 : 32|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg0_TEMP_5 : 40|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg0_TEMP_6 : 48|8@1- (1,0) [-128|127] "" Vector__XXX BO_ 649 TPDO_ACC_BOARD_Temp_1: 8 Vector__XXX - SG_ Seg1_TEMP_0 : 0|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg1_TEMP_1 : 8|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg1_TEMP_2 : 16|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg1_TEMP_3 : 24|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg1_TEMP_4 : 32|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg1_TEMP_5 : 40|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg1_TEMP_6 : 48|8@1+ (1,-40) [-40|215] "" Vector__XXX + SG_ Seg1_TEMP_0 : 0|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg1_TEMP_1 : 8|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg1_TEMP_2 : 16|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg1_TEMP_3 : 24|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg1_TEMP_4 : 32|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg1_TEMP_5 : 40|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg1_TEMP_6 : 48|8@1- (1,0) [-128|127] "" Vector__XXX BO_ 905 TPDO_ACC_BOARD_Temp_2: 8 Vector__XXX - SG_ Seg2_TEMP_0 : 0|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg2_TEMP_1 : 8|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg2_TEMP_2 : 16|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg2_TEMP_3 : 24|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg2_TEMP_4 : 32|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg2_TEMP_5 : 40|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg2_TEMP_6 : 48|8@1+ (1,-40) [-40|215] "" Vector__XXX + SG_ Seg2_TEMP_0 : 0|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg2_TEMP_1 : 8|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg2_TEMP_2 : 16|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg2_TEMP_3 : 24|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg2_TEMP_4 : 32|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg2_TEMP_5 : 40|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg2_TEMP_6 : 48|8@1- (1,0) [-128|127] "" Vector__XXX BO_ 1161 TPDO_ACC_BOARD_Temp_3: 8 Vector__XXX - SG_ Seg3_TEMP_0 : 0|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg3_TEMP_1 : 8|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg3_TEMP_2 : 16|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg3_TEMP_3 : 24|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg3_TEMP_4 : 32|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg3_TEMP_5 : 40|8@1+ (1,-40) [-40|215] "" Vector__XXX - SG_ Seg3_TEMP_6 : 48|8@1+ (1,-40) [-40|215] "" Vector__XXX + SG_ Seg3_TEMP_0 : 0|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg3_TEMP_1 : 8|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg3_TEMP_2 : 16|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg3_TEMP_3 : 24|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg3_TEMP_4 : 32|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg3_TEMP_5 : 40|8@1- (1,0) [-128|127] "" Vector__XXX + SG_ Seg3_TEMP_6 : 48|8@1- (1,0) [-128|127] "" Vector__XXX BO_ 1794 NMT_ACC_HEARTBEAT: 8 Vector__XXX SG_ Status : 0|8@1+ (1,0) [0|255] "" Vector__XXX @@ -161,6 +161,58 @@ BO_ 1160 TPDO_ACC_BOARD_Volt_3: 8 Vector__XXX SG_ Seg3_VOLT_5 : 40|8@1+ (0.02,0) [0|5.1] "V" Vector__XXX SG_ Seg3_VOLT_6 : 48|8@1+ (0.02,0) [0|5.1] "V" Vector__XXX +BO_ 390 SME_RPDO_Throttle_Demand: 8 Vector__XXX + SG_ SME_THROTL_PowerReady : 35|1@1- (1,0) [0|1] "" Vector__XXX + SG_ SME_THROTL_MBB_Alive : 40|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ SME_THROTL_Reverse : 33|1@1- (1,0) [0|1] "" Vector__XXX + SG_ SME_THROTL_Forward : 32|1@1- (1,0) [0|1] "" Vector__XXX + SG_ SME_THROTL_MaxSpeed : 16|16@1- (1,0) [-32768|32767] "RPM" Vector__XXX + SG_ SME_THROTL_TorqueDemand : 0|16@1- (1,0) [-32767|32767] "Q15" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_1 : 34|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_2 : 36|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_3 : 37|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_4 : 38|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_5 : 39|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_6 : 44|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_7 : 45|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_8 : 46|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_BIT_9 : 47|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ SME_THROTL_UNUSED_SHORT_1 : 48|16@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 646 SME_RPDO_Max_Currents: 8 Vector__XXX + SG_ SME_CURRLIM_ChargeCurrentLim : 0|16@1+ (1,0) [0|65535] "A" Vector__XXX + SG_ SME_CURRLIM_DischargeCurrentLim : 16|16@1+ (1,0) [0|65535] "A" Vector__XXX + SG_ SME_CURRLIM_UNUSED_INT_1 : 32|32@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 1153 SME_TPDO_Torque_speed: 8 Vector__XXX + SG_ SME_TRQSPD_SOC_Low_Traction : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_SOC_Low_Hydraulic : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Reverse : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Forward : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Park_Brake : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Pedal_Brake : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Controller_Overtermp : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Key_switch_overvolt : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Key_switch_undervolt : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Running : 41|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Traction : 42|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Hydraulic : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Powering_Enabled : 44|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Powering_Ready : 45|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_contactor_closed : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Precharging : 46|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SME_TRQSPD_Speed : 0|16@1+ (1,0) [-32768|32767] "RPM" Vector__XXX + SG_ SME_TRQSPD_MotorFlags : 48|16@1+ (1,0) [0|65535] "" Vector__XXX + SG_ SME_TRQSPD_Torque : 16|16@1- (1,0) [-32767|32767] "Q15" Vector__XXX + +BO_ 1665 SME_TPDO_Temperature: 8 Vector__XXX + SG_ SME_TEMP_FaultLevel : 40|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SME_TEMP_FaultCode : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SME_TEMP_DC_Bus_V : 16|16@1+ (0.1,0) [0|6553.5] "V" Vector__XXX + SG_ SME_TEMP_ControllerTemperature : 8|8@1+ (1,-40) [0|255] "C" Vector__XXX + SG_ SME_TEMP_MotorTemperature : 0|8@1+ (1,-40) [0|255] "C" Vector__XXX + SG_ SME_TEMP_BusCurrent : 48|16@1- (0.1,0) [-3276.8|3276.7] "A" Vector__XXX + CM_ SG_ 386 BMS_Fault "Fault High"; diff --git a/mainCANbus.dbf b/mainCANbus.dbf new file mode 100644 index 0000000..ed748fa --- /dev/null +++ b/mainCANbus.dbf @@ -0,0 +1,307 @@ +//******************************BUSMASTER Messages and signals Database ******************************// + +[DATABASE_VERSION] 1.3 + +[PROTOCOL] CAN + +[BUSMASTER_VERSION] [3.2.2] +[NUMBER_OF_MESSAGES] 15 + +[START_MSG] TPDO_ACC_BOARD_State,386,8,13,1,S, +[START_SIGNALS] GLV_Voltage,8,1,0,U,255,0,1,0,0.1,Volts,, +[START_SIGNALS] TS_Voltage,16,2,0,U,65535,0,1,0,0.1,Volts,, +[START_SIGNALS] BMS_Fault,1,4,0,B,1,0,1,0,1,,, +[START_SIGNALS] BMS_Balancing,1,4,1,B,1,0,1,0,1,,, +[START_SIGNALS] Precharge_Done,1,4,2,B,1,0,1,0,1,,, +[START_SIGNALS] Charging,1,4,3,B,1,0,1,0,1,,, +[START_SIGNALS] Fans_On,1,4,4,B,1,0,1,0,1,,, +[START_SIGNALS] Shutdown_Closed,1,4,5,B,1,0,1,0,1,,, +[START_SIGNALS] UNUSED_a,1,4,6,B,1,0,1,0,1,,, +[START_SIGNALS] UNUSED_b,1,4,7,B,1,0,1,0,1,,, +[START_SIGNALS] Min_Cell_Voltage,8,5,0,U,255,0,1,0,0.02,Volts,, +[START_SIGNALS] Max_Cell_Voltage,8,6,0,U,255,0,1,0,0.02,Volts,, +[START_SIGNALS] TS_Current,16,7,0,I,32767,-32768,1,0,0.1,Amps,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Temp_0,393,8,7,1,S, +[START_SIGNALS] Seg0_TEMP_0,8,1,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg0_TEMP_1,8,2,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg0_TEMP_2,8,3,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg0_TEMP_3,8,4,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg0_TEMP_4,8,5,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg0_TEMP_5,8,6,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg0_TEMP_6,8,7,0,I,127,-128,1,0,1,,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Temp_1,649,8,7,1,S, +[START_SIGNALS] Seg1_TEMP_0,8,1,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg1_TEMP_1,8,2,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg1_TEMP_2,8,3,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg1_TEMP_3,8,4,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg1_TEMP_4,8,5,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg1_TEMP_5,8,6,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg1_TEMP_6,8,7,0,I,127,-128,1,0,1,,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Temp_2,905,8,7,1,S, +[START_SIGNALS] Seg2_TEMP_0,8,1,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg2_TEMP_1,8,2,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg2_TEMP_2,8,3,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg2_TEMP_3,8,4,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg2_TEMP_4,8,5,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg2_TEMP_5,8,6,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg2_TEMP_6,8,7,0,I,127,-128,1,0,1,,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Temp_3,1161,8,7,1,S, +[START_SIGNALS] Seg3_TEMP_0,8,1,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg3_TEMP_1,8,2,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg3_TEMP_2,8,3,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg3_TEMP_3,8,4,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg3_TEMP_4,8,5,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg3_TEMP_5,8,6,0,I,127,-128,1,0,1,,, +[START_SIGNALS] Seg3_TEMP_6,8,7,0,I,127,-128,1,0,1,,, +[END_MSG] + +[START_MSG] NMT_ACC_HEARTBEAT,1794,8,1,1,S, +[START_SIGNALS] Status,8,1,0,U,255,0,1,0,1,,, +[VALUE_DESCRIPTION] "Boot up",0 +[VALUE_DESCRIPTION] "Stopped",4 +[VALUE_DESCRIPTION] "Operational",5 +[VALUE_DESCRIPTION] "Pre-operational",127 +[END_MSG] + +[START_MSG] TPDO_BSPD_BOARD_Brake,644,8,6,1,S, +[START_SIGNALS] Brake_Sensor_F,8,1,0,U,255,0,1,0,0.5,percent,, +[START_SIGNALS] Brake_Sensor_R,8,2,0,U,255,0,1,0,0.5,percent,, +[START_SIGNALS] Steering_Sensor,8,3,0,U,255,0,1,-90,1,degrees,, +[START_SIGNALS] Brakes_On,1,4,0,B,1,0,1,0,1,,, +[START_SIGNALS] IMD_Fault,1,4,1,B,1,0,1,0,1,,, +[START_SIGNALS] BSPD_Fault,1,4,2,B,1,0,1,0,1,,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Volt_0,392,8,7,1,S, +[START_SIGNALS] Seg0_VOLT_0,8,1,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg0_VOLT_1,8,2,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg0_VOLT_2,8,3,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg0_VOLT_3,8,4,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg0_VOLT_4,8,5,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg0_VOLT_5,8,6,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg0_VOLT_6,8,7,0,U,255,0,1,0,0.02,V,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Volt_1,648,8,7,1,S, +[START_SIGNALS] Seg1_VOLT_0,8,1,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg1_VOLT_1,8,2,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg1_VOLT_2,8,3,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg1_VOLT_3,8,4,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg1_VOLT_4,8,5,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg1_VOLT_5,8,6,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg1_VOLT_6,8,7,0,U,255,0,1,0,0.02,V,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Volt_2,904,8,7,1,S, +[START_SIGNALS] Seg2_VOLT_0,8,1,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg2_VOLT_1,8,2,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg2_VOLT_2,8,3,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg2_VOLT_3,8,4,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg2_VOLT_4,8,5,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg2_VOLT_5,8,6,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg2_VOLT_6,8,7,0,U,255,0,1,0,0.02,V,, +[END_MSG] + +[START_MSG] TPDO_ACC_BOARD_Volt_3,1160,8,7,1,S, +[START_SIGNALS] Seg3_VOLT_0,8,1,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg3_VOLT_1,8,2,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg3_VOLT_2,8,3,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg3_VOLT_3,8,4,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg3_VOLT_4,8,5,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg3_VOLT_5,8,6,0,U,255,0,1,0,0.02,V,, +[START_SIGNALS] Seg3_VOLT_6,8,7,0,U,255,0,1,0,0.02,V,, +[END_MSG] + +[START_MSG] SME_RPDO_Throttle_Demand,390,8,16,1,S, +[START_SIGNALS] SME_THROTL_PowerReady,1,5,3,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_MBB_Alive,4,6,0,U,15,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_Reverse,1,5,1,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_Forward,1,5,0,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_MaxSpeed,16,3,0,I,32767,-32768,1,0,1,RPM,, +[START_SIGNALS] SME_THROTL_TorqueDemand,16,1,0,I,32767,-32767,1,0,1,Q15,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_1,1,5,2,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_2,1,5,4,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_3,1,5,5,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_4,1,5,6,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_5,1,5,7,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_6,1,6,4,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_7,1,6,5,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_8,1,6,6,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_BIT_9,1,6,7,B,1,0,1,0,1,,, +[START_SIGNALS] SME_THROTL_UNUSED_SHORT_1,16,7,0,U,65535,0,1,0,1,,, +[END_MSG] + +[START_MSG] SME_RPDO_Max_Currents,646,8,3,1,S, +[START_SIGNALS] SME_CURRLIM_ChargeCurrentLim,16,1,0,U,65535,0,1,0,1,A,, +[START_SIGNALS] SME_CURRLIM_DischargeCurrentLim,16,3,0,U,65535,0,1,0,1,A,, +[START_SIGNALS] SME_CURRLIM_UNUSED_INT_1,32,5,0,U,4294967295,0,1,0,1,,, +[END_MSG] + +[START_MSG] SME_TPDO_Torque_speed,1153,8,19,1,S, +[START_SIGNALS] SME_TRQSPD_SOC_Low_Traction,1,5,0,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_SOC_Low_Hydraulic,1,5,1,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Reverse,1,5,2,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Forward,1,5,3,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Park_Brake,1,5,4,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Pedal_Brake,1,5,5,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Controller_Overtermp,1,5,6,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Key_switch_overvolt,1,5,7,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Key_switch_undervolt,1,6,0,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Running,1,6,1,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Traction,1,6,2,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Hydraulic,1,6,3,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Powering_Enabled,1,6,4,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Powering_Ready,1,6,5,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_contactor_closed,1,6,7,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Precharging,1,6,6,B,1,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Speed,16,1,0,U,32767,0,1,0,1,RPM,, +[START_SIGNALS] SME_TRQSPD_MotorFlags,16,7,0,U,65535,0,1,0,1,,, +[START_SIGNALS] SME_TRQSPD_Torque,16,3,0,I,32767,-32767,1,0,1,Q15,, +[END_MSG] + +[START_MSG] SME_TPDO_Temperature,1665,8,6,1,S, +[START_SIGNALS] SME_TEMP_FaultLevel,8,6,0,U,255,0,1,0,1,,, +[START_SIGNALS] SME_TEMP_FaultCode,8,5,0,U,255,0,1,0,1,,, +[START_SIGNALS] SME_TEMP_DC_Bus_V,16,3,0,U,65535,0,1,0,0.1,V,, +[START_SIGNALS] SME_TEMP_ControllerTemperature,8,2,0,U,255,40,1,-40,1,C,, +[START_SIGNALS] SME_TEMP_MotorTemperature,8,1,0,U,255,40,1,-40,1,C,, +[START_SIGNALS] SME_TEMP_BusCurrent,16,7,0,I,32767,-32768,1,0,0.1,A,, +[END_MSG] + +[START_SIG_LIST] +[START_SIGNALS] Max_Cell_Temp,8,1,0,U,255,0,1,-40,1,C,, +[START_SIGNALS] NewSignal_0004,8,1,0,U,255,0,1,0,1,,, +[START_SIGNALS] TEMP_0,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_1,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_2,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_3,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_4,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_5,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_6,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_0,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_1,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_2,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_3,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_4,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_5,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_6,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_0,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_1,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_2,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_3,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_4,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_5,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] TEMP_6,8,1,0,U,255,0,1,-40,1,,, +[START_SIGNALS] Volt_Segment,8,1,0,U,255,0,1,0,1,,, +[START_SIGNALS] Temp_Segment,8,1,0,U,255,0,1,0,1,,, +[END_SIG_LIST] + +[START_VALUE_TABLE] +[END_VALUE_TABLE] + +[NODE] + +[START_DESC] +[START_DESC_NET] +[END_DESC_NET] + +[START_DESC_NODE] +[END_DESC_NODE] + +[START_DESC_MSG] +[END_DESC_MSG] + +[START_DESC_SIG] +386 S BMS_Fault "Fault High"; +386 S BMS_Balancing "Balancing High"; +386 S Precharge_Done "Done High"; +386 S Charging "Charging High"; +386 S Fans_On "On High"; +386 S Shutdown_Closed "Closed High"; +644 S Steering_Sensor "90 (left) to -90 (right)"; +[END_DESC_SIG] +[END_DESC] + +[START_PARAM] +[START_PARAM_NET] +"BusType",STRING,"" +[END_PARAM_NET] + +[START_PARAM_NODE] +"ECU",STRING,"" +[END_PARAM_NODE] + +[START_PARAM_MSG] +"CANFD_BRS",ENUM,"1","0","1" +"VFrameFormat",ENUM,"StandardCAN","StandardCAN","ExtendedCAN","StandardCAN_FD","ExtendedCAN_FD" +[END_PARAM_MSG] + +[START_PARAM_SIG] +[END_PARAM_SIG] + +[START_PARAM_NODE_RX_SIG] +[END_PARAM_NODE_RX_SIG] + +[START_PARAM_NODE_TX_MSG] +[END_PARAM_NODE_TX_MSG] +[END_PARAM] + +[START_PARAM_VAL] +[START_PARAM_NET_VAL] +"BusType","CAN +[END_PARAM_NET_VAL] + +[START_PARAM_NODE_VAL] +[END_PARAM_NODE_VAL] + +[START_PARAM_MSG_VAL] +[END_PARAM_MSG_VAL] + +[START_PARAM_SIG_VAL] +[END_PARAM_SIG_VAL] + +[END_PARAM_VAL] + + +[START_NOT_SUPPORTED] +[END_NOT_SUPPORTED] + +[START_NOT_PROCESSED] + PZ_ + ON_QRS_ + ON_ + INY_ + PNG_QRS_ + PNG_ + SVYGRE + ON_QRS_QRS_ + RI_QNGN_ + RAIINE_QNGN_ + FTGLCR_ + FTGLCR_INY_ + ON_QRS_FTGLCR_ + ON_FTGLCR_ + FVT_GLCR_ERS_ + INY_GNOYR_ + FVT_TEBHC_ + FVT_INYGLCR_ + FVTGLCR_INYGLCR_ + OB_GK_OH_ + ON_QRS_ERY_ + ON_ERY_ + ON_QRS_QRS_ERY_ + OH_FT_ERY_ + OH_RI_ERY_ + OH_OB_ERY_ + FT_ZHY_INY_ +OF_: + +[END_NOT_PROCESSED] diff --git a/mainCANbus.log b/mainCANbus.log new file mode 100644 index 0000000..b517cd9 --- /dev/null +++ b/mainCANbus.log @@ -0,0 +1,59 @@ +Conversion Warnings Log + + +MSG_ID: 386 MSG_TYPE: S MSG_NAME: TPDO_ACC_BOARD_State + SIG_NAME: BMS_Fault, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: BMS_Balancing, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: Precharge_Done, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: Charging, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: Fans_On, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: Shutdown_Closed, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: UNUSED_a, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: UNUSED_b, STATUS: Invalid Max or Min value., ACTION: Value Set to default + +MSG_ID: 390 MSG_TYPE: S MSG_NAME: SME_RPDO_Throttle_Demand + SIG_NAME: SME_THROTL_UNUSED_BIT_1, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_2, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_3, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_4, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_5, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_6, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_7, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_8, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_BIT_9, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_THROTL_UNUSED_SHORT_1, STATUS: Invalid Max or Min value., ACTION: Value Set to default + +MSG_ID: 646 MSG_TYPE: S MSG_NAME: SME_RPDO_Max_Currents + SIG_NAME: SME_CURRLIM_UNUSED_INT_1, STATUS: Invalid Max or Min value., ACTION: Value Set to default + +MSG_ID: 1153 MSG_TYPE: S MSG_NAME: SME_TPDO_Torque_speed + SIG_NAME: SME_TRQSPD_Speed, STATUS: Invalid Max or Min value., ACTION: Value Set to default + +MSG_ID: 1665 MSG_TYPE: S MSG_NAME: SME_TPDO_Temperature + SIG_NAME: SME_TEMP_ControllerTemperature, STATUS: Invalid Max or Min value., ACTION: Value Set to default + SIG_NAME: SME_TEMP_MotorTemperature, STATUS: Invalid Max or Min value., ACTION: Value Set to default + +MSG_ID: 1073741824 MSG_TYPE: X MSG_NAME: VECTOR__INDEPENDENT_SIG_MSG + SIG_NAME: Max_Cell_Temp, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_0, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_1, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_2, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_3, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_4, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_5, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_6, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_0, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_1, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_2, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_3, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_4, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_5, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_6, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_0, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_1, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_2, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_3, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_4, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_5, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: TEMP_6, STATUS: No error, ACTION: Signal Discarded + SIG_NAME: Temp_Segment, STATUS: No error, ACTION: Signal Discarded