run clang-format for all files except libraries in this repository

This commit is contained in:
lenvm 2023-11-08 23:06:06 +01:00
parent cb63316cd9
commit 6b6bf57804
38 changed files with 3438 additions and 2905 deletions

View file

@ -3,33 +3,33 @@
#include <Arduino.h>
#include "HardwareSerial.h"
#include "USER_SETTINGS.h"
#include "src/battery/BATTERIES.h"
#include "src/devboard/can/ESP32CAN.h"
#include "src/devboard/config.h"
#include "src/devboard/modbus/mbServerFCs.h"
#include "src/inverter/INVERTERS.h"
#include "src/lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
#include "src/lib/adafruit-Adafruit_NeoPixel/Adafruit_NeoPixel.h"
#include "src/lib/eModbus-eModbus/Logging.h"
#include "src/lib/eModbus-eModbus/ModbusServerRTU.h"
#include "src/lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
#include "USER_SETTINGS.h"
#include "src/devboard/config.h"
#include "src/devboard/modbus/mbServerFCs.h"
#include "src/devboard/can/ESP32CAN.h"
#include "src/battery/BATTERIES.h"
#include "src/inverter/INVERTERS.h"
//CAN parameters
CAN_device_t CAN_cfg; // CAN Config
const int rx_queue_size = 10; // Receive Queue size
CAN_device_t CAN_cfg; // CAN Config
const int rx_queue_size = 10; // Receive Queue size
#ifdef DUAL_CAN
#include "src/lib/pierremolinaro-acan2515/ACAN2515.h"
static const uint32_t QUARTZ_FREQUENCY = 8UL * 1000UL * 1000UL ; // 8 MHz
ACAN2515 can(MCP2515_CS, SPI, MCP2515_INT);
static ACAN2515_Buffer16 gBuffer;
#include "src/lib/pierremolinaro-acan2515/ACAN2515.h"
static const uint32_t QUARTZ_FREQUENCY = 8UL * 1000UL * 1000UL; // 8 MHz
ACAN2515 can(MCP2515_CS, SPI, MCP2515_INT);
static ACAN2515_Buffer16 gBuffer;
#endif
//Interval settings
int intervalInverterTask = 4800; //Interval at which to refresh modbus registers / inverter values
const int interval10 = 10; //Interval for 10ms tasks
int intervalInverterTask = 4800; //Interval at which to refresh modbus registers / inverter values
const int interval10 = 10; //Interval for 10ms tasks
unsigned long previousMillis10ms = 50;
unsigned long previousMillisInverter = 0;
unsigned long previousMillisInverter = 0;
//ModbusRTU parameters
#if defined(BYD_MODBUS)
@ -53,9 +53,9 @@ ModbusServerRTU MBserver(Serial2, 2000);
#define UPDATING 5
//Common inverter parameters
uint16_t capacity_Wh_startup = BATTERY_WH_MAX;
uint16_t max_power = 40960; //41kW
const uint16_t max_voltage = ABSOLUTE_MAX_VOLTAGE; //if higher charging is not possible (goes into forced discharge)
const uint16_t min_voltage = ABSOLUTE_MIN_VOLTAGE; //if lower Gen24 disables battery
uint16_t max_power = 40960; //41kW
const uint16_t max_voltage = ABSOLUTE_MAX_VOLTAGE; //if higher charging is not possible (goes into forced discharge)
const uint16_t min_voltage = ABSOLUTE_MIN_VOLTAGE; //if lower Gen24 disables battery
uint16_t min_volt_byd_can = min_voltage;
uint16_t max_volt_byd_can = max_voltage;
uint16_t min_volt_solax_can = min_voltage;
@ -68,19 +68,20 @@ uint16_t min_volt_sma_can = min_voltage;
uint16_t max_volt_sma_can = max_voltage;
uint16_t battery_voltage = 3700;
uint16_t battery_current = 0;
uint16_t SOC = 5000; //SOC 0-100.00% //Updates later on from CAN
uint16_t StateOfHealth = 9900; //SOH 0-100.00% //Updates later on from CAN
uint16_t capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
uint16_t remaining_capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
uint16_t max_target_discharge_power = 0; //0W (0W > restricts to no discharge) //Updates later on from CAN
uint16_t max_target_charge_power = 4312; //4.3kW (during charge), both 307&308 can be set (>0) at the same time //Updates later on from CAN. Max value is 30000W
uint16_t temperature_max = 50; //reads from battery later
uint16_t temperature_min = 60; //reads from battery later
uint16_t bms_char_dis_status; //0 idle, 1 discharging, 2, charging
uint16_t bms_status = ACTIVE; //ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
uint16_t stat_batt_power = 0; //power going in/out of battery
uint16_t cell_max_voltage = 3700; //Stores the highest cell voltage value in the system
uint16_t cell_min_voltage = 3700; //Stores the minimum cell voltage value in the system
uint16_t SOC = 5000; //SOC 0-100.00% //Updates later on from CAN
uint16_t StateOfHealth = 9900; //SOH 0-100.00% //Updates later on from CAN
uint16_t capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
uint16_t remaining_capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
uint16_t max_target_discharge_power = 0; //0W (0W > restricts to no discharge) //Updates later on from CAN
uint16_t max_target_charge_power =
4312; //4.3kW (during charge), both 307&308 can be set (>0) at the same time //Updates later on from CAN. Max value is 30000W
uint16_t temperature_max = 50; //reads from battery later
uint16_t temperature_min = 60; //reads from battery later
uint16_t bms_char_dis_status; //0 idle, 1 discharging, 2, charging
uint16_t bms_status = ACTIVE; //ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
uint16_t stat_batt_power = 0; //power going in/out of battery
uint16_t cell_max_voltage = 3700; //Stores the highest cell voltage value in the system
uint16_t cell_min_voltage = 3700; //Stores the minimum cell voltage value in the system
// LED control
#define GREEN 0
@ -95,23 +96,15 @@ const uint8_t maxBrightness = 100;
uint8_t LEDcolor = GREEN;
//Contactor parameters
enum State {
DISCONNECTED,
PRECHARGE,
NEGATIVE,
POSITIVE,
PRECHARGE_OFF,
COMPLETED,
SHUTDOWN_REQUESTED
};
enum State { DISCONNECTED, PRECHARGE, NEGATIVE, POSITIVE, PRECHARGE_OFF, COMPLETED, SHUTDOWN_REQUESTED };
State contactorStatus = DISCONNECTED;
#define MAX_ALLOWED_FAULT_TICKS 500
#define PRECHARGE_TIME_MS 160
#define NEGATIVE_CONTACTOR_TIME_MS 1000
#define POSITIVE_CONTACTOR_TIME_MS 2000
#define PWM_Freq 20000 // 20 kHz frequency, beyond audible range
#define PWM_Res 10 // 10 Bit resolution 0 to 1023, maps 'nicely' to 0% 100%
#define PWM_Freq 20000 // 20 kHz frequency, beyond audible range
#define PWM_Res 10 // 10 Bit resolution 0 to 1023, maps 'nicely' to 0% 100%
#define PWM_Hold_Duty 250
#define POSITIVE_PWM_Ch 0
#define NEGATIVE_PWM_Ch 1
@ -122,54 +115,50 @@ uint8_t batteryAllowsContactorClosing = 0;
uint8_t inverterAllowsContactorClosing = 1;
// Setup() - initialization happens here
void setup()
{
void setup() {
// Init Serial monitor
Serial.begin(115200);
while (!Serial)
{
}
Serial.println("__ OK __");
Serial.begin(115200);
while (!Serial) {}
Serial.println("__ OK __");
//CAN pins
pinMode(CAN_SE_PIN, OUTPUT);
digitalWrite(CAN_SE_PIN, LOW);
CAN_cfg.speed = CAN_SPEED_500KBPS;
CAN_cfg.tx_pin_id = GPIO_NUM_27;
CAN_cfg.rx_pin_id = GPIO_NUM_26;
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
// Init CAN Module
ESP32Can.CANInit();
Serial.println(CAN_cfg.speed);
//CAN pins
pinMode(CAN_SE_PIN, OUTPUT);
digitalWrite(CAN_SE_PIN, LOW);
CAN_cfg.speed = CAN_SPEED_500KBPS;
CAN_cfg.tx_pin_id = GPIO_NUM_27;
CAN_cfg.rx_pin_id = GPIO_NUM_26;
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
// Init CAN Module
ESP32Can.CANInit();
Serial.println(CAN_cfg.speed);
#ifdef DUAL_CAN
Serial.println("Dual CAN Bus (ESP32+MCP2515) selected");
gBuffer.initWithSize(25);
SPI.begin(MCP2515_SCK, MCP2515_MISO, MCP2515_MOSI);
Serial.println ("Configure ACAN2515") ;
ACAN2515Settings settings (QUARTZ_FREQUENCY, 500UL * 1000UL) ; // CAN bit rate 500 kb/s
settings.mRequestedMode = ACAN2515Settings::NormalMode ; // Select loopback mode
can.begin (settings, [] { can.isr (); });
#endif
#ifdef DUAL_CAN
Serial.println("Dual CAN Bus (ESP32+MCP2515) selected");
gBuffer.initWithSize(25);
SPI.begin(MCP2515_SCK, MCP2515_MISO, MCP2515_MOSI);
Serial.println("Configure ACAN2515");
ACAN2515Settings settings(QUARTZ_FREQUENCY, 500UL * 1000UL); // CAN bit rate 500 kb/s
settings.mRequestedMode = ACAN2515Settings::NormalMode; // Select loopback mode
can.begin(settings, [] { can.isr(); });
#endif
//Init contactor pins
#ifdef CONTACTOR_CONTROL
//Init contactor pins
#ifdef CONTACTOR_CONTROL
pinMode(POSITIVE_CONTACTOR_PIN, OUTPUT);
digitalWrite(POSITIVE_CONTACTOR_PIN, LOW);
digitalWrite(POSITIVE_CONTACTOR_PIN, LOW);
pinMode(NEGATIVE_CONTACTOR_PIN, OUTPUT);
digitalWrite(NEGATIVE_CONTACTOR_PIN, LOW);
#ifdef PWM_CONTACTOR_CONTROL
ledcSetup(POSITIVE_PWM_Ch, PWM_Freq, PWM_Res); // Setup PWM Channel Frequency and Resolution
ledcSetup(NEGATIVE_PWM_Ch, PWM_Freq, PWM_Res); // Setup PWM Channel Frequency and Resolution
ledcAttachPin(POSITIVE_CONTACTOR_PIN, POSITIVE_PWM_Ch); // Attach Positive Contactor Pin to Hardware PWM Channel
ledcAttachPin(NEGATIVE_CONTACTOR_PIN, NEGATIVE_PWM_Ch); // Attach Positive Contactor Pin to Hardware PWM Channel
ledcWrite(POSITIVE_PWM_Ch, 0); // Set Positive PWM to 0%
ledcWrite(NEGATIVE_PWM_Ch, 0); // Set Negative PWM to 0%
#endif
digitalWrite(NEGATIVE_CONTACTOR_PIN, LOW);
#ifdef PWM_CONTACTOR_CONTROL
ledcSetup(POSITIVE_PWM_Ch, PWM_Freq, PWM_Res); // Setup PWM Channel Frequency and Resolution
ledcSetup(NEGATIVE_PWM_Ch, PWM_Freq, PWM_Res); // Setup PWM Channel Frequency and Resolution
ledcAttachPin(POSITIVE_CONTACTOR_PIN, POSITIVE_PWM_Ch); // Attach Positive Contactor Pin to Hardware PWM Channel
ledcAttachPin(NEGATIVE_CONTACTOR_PIN, NEGATIVE_PWM_Ch); // Attach Positive Contactor Pin to Hardware PWM Channel
ledcWrite(POSITIVE_PWM_Ch, 0); // Set Positive PWM to 0%
ledcWrite(NEGATIVE_PWM_Ch, 0); // Set Negative PWM to 0%
#endif
pinMode(PRECHARGE_PIN, OUTPUT);
digitalWrite(PRECHARGE_PIN, LOW);
#endif
digitalWrite(PRECHARGE_PIN, LOW);
#endif
//Set up Modbus RTU Server
pinMode(RS485_EN_PIN, OUTPUT);
@ -179,11 +168,11 @@ void setup()
pinMode(PIN_5V_EN, OUTPUT);
digitalWrite(PIN_5V_EN, HIGH);
#ifdef BYD_MODBUS
#ifdef BYD_MODBUS
// Init Static data to the RTU Modbus
handle_static_data_modbus_byd();
#endif
#if defined(BYD_MODBUS) || defined(LUNA2000_MODBUS)
#endif
#if defined(BYD_MODBUS) || defined(LUNA2000_MODBUS)
// Init Serial2 connected to the RTU Modbus
RTUutils::prepareHardwareSerial(Serial2);
Serial2.begin(9600, SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
@ -194,304 +183,287 @@ void setup()
MBserver.registerWorker(MBTCP_ID, R_W_MULT_REGISTERS, &FC23);
// Start ModbusRTU background task
MBserver.begin(Serial2);
#endif
#endif
// Init LED control
pixels.begin();
//Inform user what Inverter is used
#ifdef BYD_CAN
//Inform user what Inverter is used
#ifdef BYD_CAN
Serial.println("BYD CAN protocol selected");
#endif
#ifdef BYD_MODBUS
#endif
#ifdef BYD_MODBUS
Serial.println("BYD Modbus RTU protocol selected");
#endif
#ifdef LUNA2000_MODBUS
#endif
#ifdef LUNA2000_MODBUS
Serial.println("Luna2000 Modbus RTU protocol selected");
#endif
#ifdef PYLON_CAN
Serial.println("PYLON CAN protocol selected")
#endif
#ifdef SMA_CAN
Serial.println("SMA CAN protocol selected");
#endif
#ifdef SOFAR_CAN
#endif
#ifdef PYLON_CAN
Serial
.println("PYLON CAN protocol selected")
#endif
#ifdef SMA_CAN
Serial.println("SMA CAN protocol selected");
#endif
#ifdef SOFAR_CAN
Serial.println("SOFAR CAN protocol selected");
#endif
#ifdef SOLAX_CAN
inverterAllowsContactorClosing = 0; //The inverter needs to allow first on this protocol
intervalInverterTask = 800; //This protocol also requires the values to be updated faster
#endif
#ifdef SOLAX_CAN
inverterAllowsContactorClosing = 0; //The inverter needs to allow first on this protocol
intervalInverterTask = 800; //This protocol also requires the values to be updated faster
Serial.println("SOLAX CAN protocol selected");
#endif
//Inform user what battery is used
#ifdef BMW_I3_BATTERY
#endif
//Inform user what battery is used
#ifdef BMW_I3_BATTERY
Serial.println("BMW i3 battery selected");
#endif
#ifdef CHADEMO_BATTERY
#endif
#ifdef CHADEMO_BATTERY
Serial.println("Chademo battery selected");
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
Serial.println("Mitsubishi i-MiEV / Citroen C-Zero / Peugeot Ion battery selected");
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
Serial.println("Kia Niro / Hyundai Kona 64kWh battery selected");
#endif
#ifdef NISSAN_LEAF_BATTERY
#endif
#ifdef NISSAN_LEAF_BATTERY
Serial.println("Nissan LEAF battery selected");
#endif
#ifdef RENAULT_ZOE_BATTERY
#endif
#ifdef RENAULT_ZOE_BATTERY
Serial.println("Renault Zoe / Kangoo battery selected");
#endif
#ifdef TESLA_MODEL_3_BATTERY
#endif
#ifdef TESLA_MODEL_3_BATTERY
Serial.println("Tesla Model 3 battery selected");
#endif
#endif
}
// perform main program functions
void loop()
{
handle_can(); //runs as fast as possible, handle CAN routines
#ifdef DUAL_CAN
handle_can2();
#endif
if (millis() - previousMillis10ms >= interval10) //every 10ms
{
previousMillis10ms = millis();
handle_LED_state(); //Set the LED color according to state
#ifdef CONTACTOR_CONTROL
void loop() {
handle_can(); //runs as fast as possible, handle CAN routines
#ifdef DUAL_CAN
handle_can2();
#endif
if (millis() - previousMillis10ms >= interval10) //every 10ms
{
previousMillis10ms = millis();
handle_LED_state(); //Set the LED color according to state
#ifdef CONTACTOR_CONTROL
handle_contactors(); //Take care of startup precharge/contactor closing
#endif
#endif
}
if (millis() - previousMillisInverter >= intervalInverterTask) //every 5s
{
previousMillisInverter = millis();
handle_inverter(); //Update values heading towards inverter
}
if (millis() - previousMillisInverter >= intervalInverterTask) //every 5s
{
previousMillisInverter = millis();
handle_inverter(); //Update values heading towards inverter
}
}
void handle_can()
{ //This section checks if we have a complete CAN message incoming
void handle_can() { //This section checks if we have a complete CAN message incoming
//Depending on which battery/inverter is selected, we forward this to their respective CAN routines
CAN_frame_t rx_frame;
if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, 3 * portTICK_PERIOD_MS) == pdTRUE)
{
if (rx_frame.FIR.B.FF == CAN_frame_std)
{
//printf("New standard frame");
// battery
#ifdef BMW_I3_BATTERY
if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, 3 * portTICK_PERIOD_MS) == pdTRUE) {
if (rx_frame.FIR.B.FF == CAN_frame_std) {
//printf("New standard frame");
// battery
#ifdef BMW_I3_BATTERY
receive_can_i3_battery(rx_frame);
#endif
#ifdef CHADEMO_BATTERY
#endif
#ifdef CHADEMO_BATTERY
receive_can_chademo(rx_frame);
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
receive_can_imiev_battery(rx_frame);
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
receive_can_kiaHyundai_64_battery(rx_frame);
#endif
#ifdef NISSAN_LEAF_BATTERY
#endif
#ifdef NISSAN_LEAF_BATTERY
receive_can_leaf_battery(rx_frame);
#endif
#ifdef RENAULT_ZOE_BATTERY
#endif
#ifdef RENAULT_ZOE_BATTERY
receive_can_zoe_battery(rx_frame);
#endif
#ifdef TESLA_MODEL_3_BATTERY
receive_can_tesla_model_3_battery(rx_frame);
#endif
// inverter
#ifdef BYD_CAN
#endif
#ifdef TESLA_MODEL_3_BATTERY
receive_can_tesla_model_3_battery(rx_frame);
#endif
// inverter
#ifdef BYD_CAN
receive_can_byd(rx_frame);
#endif
#ifdef SMA_CAN
#endif
#ifdef SMA_CAN
receive_can_sma(rx_frame);
#endif
}
else
{
//printf("New extended frame");
#ifdef PYLON_CAN
#endif
} else {
//printf("New extended frame");
#ifdef PYLON_CAN
receive_can_pylon(rx_frame);
#endif
#ifdef SOFAR_CAN
#endif
#ifdef SOFAR_CAN
receive_can_sofar(rx_frame);
#endif
#ifdef SOLAX_CAN
#endif
#ifdef SOLAX_CAN
receive_can_solax(rx_frame);
#endif
#endif
}
}
//When we are done checking if a CAN message has arrived, we can focus on sending CAN messages
//Inverter sending
#ifdef BYD_CAN
//When we are done checking if a CAN message has arrived, we can focus on sending CAN messages
//Inverter sending
#ifdef BYD_CAN
send_can_byd();
#endif
#ifdef SMA_CAN
#endif
#ifdef SMA_CAN
send_can_sma();
#endif
#ifdef SOFAR_CAN
#endif
#ifdef SOFAR_CAN
send_can_sofar();
#endif
//Battery sending
#ifdef BMW_I3_BATTERY
#endif
//Battery sending
#ifdef BMW_I3_BATTERY
send_can_i3_battery();
#endif
#ifdef CHADEMO_BATTERY
#endif
#ifdef CHADEMO_BATTERY
send_can_chademo_battery();
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
send_can_imiev_battery();
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
send_can_kiaHyundai_64_battery();
#endif
#ifdef NISSAN_LEAF_BATTERY
#endif
#ifdef NISSAN_LEAF_BATTERY
send_can_leaf_battery();
#endif
#ifdef RENAULT_ZOE_BATTERY
#endif
#ifdef RENAULT_ZOE_BATTERY
send_can_zoe_battery();
#endif
#ifdef TESLA_MODEL_3_BATTERY
send_can_tesla_model_3_battery();
#endif
#endif
#ifdef TESLA_MODEL_3_BATTERY
send_can_tesla_model_3_battery();
#endif
}
#ifdef DUAL_CAN
void handle_can2()
{ //This function is similar to handle_can, but just takes care of inverters in the 2nd bus.
void handle_can2() { //This function is similar to handle_can, but just takes care of inverters in the 2nd bus.
//Depending on which inverter is selected, we forward this to their respective CAN routines
CAN_frame_t rx_frame2; //Struct with ESP32Can library format, compatible with the rest of the program
CANMessage MCP2515Frame; //Struct with ACAN2515 library format, needed to use thw MCP2515 library
if ( can.available() )
{
CAN_frame_t rx_frame2; //Struct with ESP32Can library format, compatible with the rest of the program
CANMessage MCP2515Frame; //Struct with ACAN2515 library format, needed to use thw MCP2515 library
if (can.available()) {
can.receive(MCP2515Frame);
rx_frame2.MsgID = MCP2515Frame.id;
rx_frame2.FIR.B.FF = MCP2515Frame.ext ? CAN_frame_ext : CAN_frame_std;
rx_frame2.FIR.B.RTR = MCP2515Frame.rtr ? CAN_RTR : CAN_no_RTR;
rx_frame2.FIR.B.DLC = MCP2515Frame.len;
for (uint8_t i=0 ; i<MCP2515Frame.len ; i++) {
rx_frame2.data.u8[i] = MCP2515Frame.data[i] ;
}
if (rx_frame2.FIR.B.FF == CAN_frame_std)
{
//Serial.println("New standard frame");
#ifdef BYD_CAN
receive_can_byd(rx_frame2);
#endif
for (uint8_t i = 0; i < MCP2515Frame.len; i++) {
rx_frame2.data.u8[i] = MCP2515Frame.data[i];
}
else
{
if (rx_frame2.FIR.B.FF == CAN_frame_std) {
//Serial.println("New standard frame");
#ifdef BYD_CAN
receive_can_byd(rx_frame2);
#endif
} else {
//Serial.println("New extended frame");
#ifdef PYLON_CAN
receive_can_pylon(rx_frame2);
#endif
#ifdef SOLAX_CAN
#ifdef PYLON_CAN
receive_can_pylon(rx_frame2);
#endif
#ifdef SOLAX_CAN
receive_can_solax(rx_frame2);
#endif
#endif
}
}
//When we are done checking if a CAN message has arrived, we can focus on sending CAN messages
//Inverter sending
#ifdef BYD_CAN
//When we are done checking if a CAN message has arrived, we can focus on sending CAN messages
//Inverter sending
#ifdef BYD_CAN
send_can_byd();
#endif
#endif
}
#endif
void handle_inverter()
{
// battery
#ifdef BMW_I3_BATTERY
update_values_i3_battery(); //Map the values to the correct registers
#endif
#ifdef CHADEMO_BATTERY
update_values_can_chademo();
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
update_values_imiev_battery(); //Map the values to the correct registers
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
update_values_kiaHyundai_64_battery(); //Map the values to the correct registers
#endif
#ifdef NISSAN_LEAF_BATTERY
update_values_leaf_battery(); //Map the values to the correct registers
#endif
#ifdef RENAULT_ZOE_BATTERY
update_values_zoe_battery(); //Map the values to the correct registers
#endif
#ifdef TESLA_MODEL_3_BATTERY
update_values_tesla_model_3_battery(); //Map the values to the correct registers
#endif
// inverter
#ifdef BYD_CAN
update_values_can_byd();
#endif
#ifdef BYD_MODBUS
update_modbus_registers_byd();
#endif
#ifdef LUNA2000_MODBUS
update_modbus_registers_luna2000();
#endif
#ifdef PYLON_CAN
update_values_can_pylon();
#endif
#ifdef SMA_CAN
update_values_can_sma();
#endif
#ifdef SOLAX_CAN
update_values_can_solax();
#endif
void handle_inverter() {
// battery
#ifdef BMW_I3_BATTERY
update_values_i3_battery(); //Map the values to the correct registers
#endif
#ifdef CHADEMO_BATTERY
update_values_can_chademo();
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
update_values_imiev_battery(); //Map the values to the correct registers
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
update_values_kiaHyundai_64_battery(); //Map the values to the correct registers
#endif
#ifdef NISSAN_LEAF_BATTERY
update_values_leaf_battery(); //Map the values to the correct registers
#endif
#ifdef RENAULT_ZOE_BATTERY
update_values_zoe_battery(); //Map the values to the correct registers
#endif
#ifdef TESLA_MODEL_3_BATTERY
update_values_tesla_model_3_battery(); //Map the values to the correct registers
#endif
// inverter
#ifdef BYD_CAN
update_values_can_byd();
#endif
#ifdef BYD_MODBUS
update_modbus_registers_byd();
#endif
#ifdef LUNA2000_MODBUS
update_modbus_registers_luna2000();
#endif
#ifdef PYLON_CAN
update_values_can_pylon();
#endif
#ifdef SMA_CAN
update_values_can_sma();
#endif
#ifdef SOLAX_CAN
update_values_can_solax();
#endif
}
#ifdef CONTACTOR_CONTROL
void handle_contactors()
{
void handle_contactors() {
//First check if we have any active errors, incase we do, turn off the battery
if(bms_status == FAULT){
if (bms_status == FAULT) {
timeSpentInFaultedMode++;
}
else{
} else {
timeSpentInFaultedMode = 0;
}
if(timeSpentInFaultedMode > MAX_ALLOWED_FAULT_TICKS)
{
if (timeSpentInFaultedMode > MAX_ALLOWED_FAULT_TICKS) {
contactorStatus = SHUTDOWN_REQUESTED;
}
if(contactorStatus == SHUTDOWN_REQUESTED)
{
if (contactorStatus == SHUTDOWN_REQUESTED) {
digitalWrite(PRECHARGE_PIN, LOW);
digitalWrite(NEGATIVE_CONTACTOR_PIN, LOW);
digitalWrite(POSITIVE_CONTACTOR_PIN, LOW);
return; //A fault scenario latches the contactor control. It is not possible to recover without a powercycle (and investigation why fault occured)
return; //A fault scenario latches the contactor control. It is not possible to recover without a powercycle (and investigation why fault occured)
}
//After that, check if we are OK to start turning on the battery
if(contactorStatus == DISCONNECTED)
{
if (contactorStatus == DISCONNECTED) {
digitalWrite(PRECHARGE_PIN, LOW);
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(POSITIVE_PWM_Ch, 0);
ledcWrite(NEGATIVE_PWM_Ch, 0);
#endif
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(POSITIVE_PWM_Ch, 0);
ledcWrite(NEGATIVE_PWM_Ch, 0);
#endif
if(batteryAllowsContactorClosing && inverterAllowsContactorClosing)
{
if (batteryAllowsContactorClosing && inverterAllowsContactorClosing) {
contactorStatus = PRECHARGE;
}
}
//Incase the inverter requests contactors to open, set the state accordingly
if(contactorStatus == COMPLETED)
{
if (!inverterAllowsContactorClosing) contactorStatus = DISCONNECTED;
if (contactorStatus == COMPLETED) {
if (!inverterAllowsContactorClosing)
contactorStatus = DISCONNECTED;
//Skip running the state machine below if it has already completed
return;
}
@ -508,9 +480,9 @@ void handle_contactors()
case NEGATIVE:
if (currentTime - prechargeStartTime >= PRECHARGE_TIME_MS) {
digitalWrite(NEGATIVE_CONTACTOR_PIN, HIGH);
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(NEGATIVE_PWM_Ch, 1023);
#endif
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(NEGATIVE_PWM_Ch, 1023);
#endif
negativeStartTime = currentTime;
contactorStatus = POSITIVE;
}
@ -519,9 +491,9 @@ void handle_contactors()
case POSITIVE:
if (currentTime - negativeStartTime >= NEGATIVE_CONTACTOR_TIME_MS) {
digitalWrite(POSITIVE_CONTACTOR_PIN, HIGH);
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(POSITIVE_PWM_Ch, 1023);
#endif
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(POSITIVE_PWM_Ch, 1023);
#endif
contactorStatus = PRECHARGE_OFF;
}
break;
@ -529,57 +501,51 @@ void handle_contactors()
case PRECHARGE_OFF:
if (currentTime - negativeStartTime >= POSITIVE_CONTACTOR_TIME_MS) {
digitalWrite(PRECHARGE_PIN, LOW);
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(NEGATIVE_PWM_Ch, PWM_Hold_Duty);
ledcWrite(POSITIVE_PWM_Ch, PWM_Hold_Duty);
#endif
#ifdef PWM_CONTACTOR_CONTROL
ledcWrite(NEGATIVE_PWM_Ch, PWM_Hold_Duty);
ledcWrite(POSITIVE_PWM_Ch, PWM_Hold_Duty);
#endif
contactorStatus = COMPLETED;
}
break;
default:
break;
break;
}
}
#endif
void handle_LED_state()
{
void handle_LED_state() {
// Determine how bright the LED should be
if (rampUp && brightness < maxBrightness){
if (rampUp && brightness < maxBrightness) {
brightness++;
}
else if (rampUp && brightness == maxBrightness){
} else if (rampUp && brightness == maxBrightness) {
rampUp = false;
}
else if (!rampUp && brightness > 0){
} else if (!rampUp && brightness > 0) {
brightness--;
}
else if (!rampUp && brightness == 0){
} else if (!rampUp && brightness == 0) {
rampUp = true;
}
switch (LEDcolor)
{
switch (LEDcolor) {
case GREEN:
pixels.setPixelColor(0, pixels.Color(0, brightness, 0)); // Green pulsing LED
break;
pixels.setPixelColor(0, pixels.Color(0, brightness, 0)); // Green pulsing LED
break;
case YELLOW:
pixels.setPixelColor(0, pixels.Color(brightness, brightness, 0)); // Yellow pulsing LED
break;
pixels.setPixelColor(0, pixels.Color(brightness, brightness, 0)); // Yellow pulsing LED
break;
case BLUE:
pixels.setPixelColor(0, pixels.Color(0, 0, brightness)); //Blue pulsing LED
break;
pixels.setPixelColor(0, pixels.Color(0, 0, brightness)); //Blue pulsing LED
break;
case RED:
pixels.setPixelColor(0, pixels.Color(150, 0, 0)); // Red LED full brightness
break;
pixels.setPixelColor(0, pixels.Color(150, 0, 0)); // Red LED full brightness
break;
default:
break;
break;
}
//BMS in fault state overrides everything
if(bms_status == FAULT)
{
pixels.setPixelColor(0, pixels.Color(255, 0, 0)); // Red LED full brightness
if (bms_status == FAULT) {
pixels.setPixelColor(0, pixels.Color(255, 0, 0)); // Red LED full brightness
}
pixels.show(); // This sends the updated pixel color to the hardware.
}
pixels.show(); // This sends the updated pixel color to the hardware.
}

View file

@ -16,25 +16,30 @@
/* Select inverter communication protocol. See Wiki for which to use with your inverter: https://github.com/dalathegreat/BYD-Battery-Emulator-For-Gen24/wiki */
//#define BYD_CAN //Enable this line to emulate a "BYD Battery-Box Premium HVS" over CAN Bus
#define BYD_MODBUS //Enable this line to emulate a "BYD 11kWh HVM battery" over Modbus RTU
#define BYD_MODBUS //Enable this line to emulate a "BYD 11kWh HVM battery" over Modbus RTU
//#define LUNA2000_MODBUS //Enable this line to emulate a "Luna2000 battery" over Modbus RTU
//#define PYLON_CAN //Enable this line to emulate a "Pylontech battery" over CAN bus
//#define PYLON_CAN //Enable this line to emulate a "Pylontech battery" over CAN bus
//#define SMA_CAN //Enable this line to emulate a "BYD Battery-Box H 8.9kWh, 7 mod" over CAN bus
//#define SOFAR_CAN //Enable this line to emulate a "Sofar Energy Storage Inverter High Voltage BMS General Protocol (Extended Frame)" over CAN bus
//#define SOLAX_CAN //Enable this line to emulate a "SolaX Triple Power LFP" over CAN bus
/* Battery settings */
#define BATTERY_WH_MAX 30000 //Battery size in Wh (Maximum value for most inverters is 60000 [60kWh], you can use larger batteries but do not set value over 60000!
#define MAXPERCENTAGE 800 //80.0% , Max percentage the battery will charge to (App will show 100% once this value is reached)
#define MINPERCENTAGE 200 //20.0% , Min percentage the battery will discharge to (App will show 0% once this value is reached)
#define MAXCHARGEAMP 300 //30.0A , BYD CAN specific setting, Max charge speed in Amp (Some inverters needs to be artificially limited)
#define MAXDISCHARGEAMP 300 //30.0A , BYD CAN specific setting, Max discharge speed in Amp (Some inverters needs to be artificially limited)
#define BATTERY_WH_MAX \
30000 //Battery size in Wh (Maximum value for most inverters is 60000 [60kWh], you can use larger batteries but do not set value over 60000!
#define MAXPERCENTAGE \
800 //80.0% , Max percentage the battery will charge to (App will show 100% once this value is reached)
#define MINPERCENTAGE \
200 //20.0% , Min percentage the battery will discharge to (App will show 0% once this value is reached)
#define MAXCHARGEAMP \
300 //30.0A , BYD CAN specific setting, Max charge speed in Amp (Some inverters needs to be artificially limited)
#define MAXDISCHARGEAMP \
300 //30.0A , BYD CAN specific setting, Max discharge speed in Amp (Some inverters needs to be artificially limited)
//define INTERLOCK_REQUIRED //Nissan LEAF specific setting, if enabled requires both high voltage conenctors to be seated before starting
/* Other options */
#define DEBUG_VIA_USB //Enable this line to have the USB port output serial diagnostic data while program runs
#define DEBUG_VIA_USB //Enable this line to have the USB port output serial diagnostic data while program runs
//#define CONTACTOR_CONTROL //Enable this line to have pins 25,32,33 handle automatic precharge/contactor+/contactor- closing sequence
//#define PWM_CONTACTOR_CONTROL //Enable this line to use PWM logic for contactors, which lower power consumption and heat generation
//#define DUAL_CAN //Enable this line to activate an isolated secondary CAN Bus using add-on MCP2515 controller (Needed for FoxESS inverters)
#endif
#endif

View file

@ -2,31 +2,31 @@
#define BATTERIES_H
#ifdef BMW_I3_BATTERY
#include "BMW-I3-BATTERY.h" //See this file for more i3 battery settings
#include "BMW-I3-BATTERY.h" //See this file for more i3 battery settings
#endif
#ifdef CHADEMO_BATTERY
#include "CHADEMO-BATTERY.h" //See this file for more Chademo settings
#include "CHADEMO-BATTERY.h" //See this file for more Chademo settings
#endif
#ifdef IMIEV_CZERO_ION_BATTERY
#include "IMIEV-CZERO-ION-BATTERY.h" //See this file for more triplet battery settings
#include "IMIEV-CZERO-ION-BATTERY.h" //See this file for more triplet battery settings
#endif
#ifdef KIA_HYUNDAI_64_BATTERY
#include "KIA-HYUNDAI-64-BATTERY.h" //See this file for more 64kWh battery settings
#include "KIA-HYUNDAI-64-BATTERY.h" //See this file for more 64kWh battery settings
#endif
#ifdef NISSAN_LEAF_BATTERY
#include "NISSAN-LEAF-BATTERY.h" //See this file for more LEAF battery settings
#include "NISSAN-LEAF-BATTERY.h" //See this file for more LEAF battery settings
#endif
#ifdef RENAULT_ZOE_BATTERY
#include "RENAULT-ZOE-BATTERY.h" //See this file for more Zoe battery settings
#include "RENAULT-ZOE-BATTERY.h" //See this file for more Zoe battery settings
#endif
#ifdef TESLA_MODEL_3_BATTERY
#include "TESLA-MODEL-3-BATTERY.h" //See this file for more Tesla battery settings
#include "TESLA-MODEL-3-BATTERY.h" //See this file for more Tesla battery settings
#endif
#endif
#endif

View file

@ -7,22 +7,37 @@
// Check if I3 battery stays alive with only 10B and 512. If not, add 12F. If that doesn't help, add more from CAN log (ask Dala)
/* Do not change code below unless you are sure what you are doing */
static unsigned long previousMillis20 = 0; // will store last time a 20ms CAN Message was send
static unsigned long previousMillis600 = 0; // will store last time a 600ms CAN Message was send
static const int interval20 = 20; // interval (ms) at which send CAN Messages
static const int interval600 = 600; // interval (ms) at which send CAN Messages
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static unsigned long previousMillis20 = 0; // will store last time a 20ms CAN Message was send
static unsigned long previousMillis600 = 0; // will store last time a 600ms CAN Message was send
static const int interval20 = 20; // interval (ms) at which send CAN Messages
static const int interval600 = 600; // interval (ms) at which send CAN Messages
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
#define LB_MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to Inverter
#define LB_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to Inverter
#define LB_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to Inverter
CAN_frame_t BMW_10B = {.FIR = {.B = {.DLC = 3,.FF = CAN_frame_std,}},.MsgID = 0x10B,.data = {0xCD, 0x01, 0xFC}};
CAN_frame_t BMW_512 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x512,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x12}}; //0x512 Network management edme VCU
//CAN_frame_t BMW_12F //Might be needed, Wake up ,VCU 100ms
CAN_frame_t BMW_10B = {.FIR = {.B =
{
.DLC = 3,
.FF = CAN_frame_std,
}},
.MsgID = 0x10B,
.data = {0xCD, 0x01, 0xFC}};
CAN_frame_t BMW_512 = {
.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x512,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x12}}; //0x512 Network management edme VCU
//CAN_frame_t BMW_12F //Might be needed, Wake up ,VCU 100ms
//These CAN messages need to be sent towards the battery to keep it alive
static const uint8_t BMW_10B_0[15] = {0xCD,0x19,0x94,0x6D,0xE0,0x34,0x78,0xDB,0x97,0x43,0x0F,0xF6,0xBA,0x6E,0x81};
static const uint8_t BMW_10B_1[15] = {0x01,0x02,0x33,0x34,0x05,0x06,0x07,0x08,0x09,0x0A,0x0B,0x0C,0x0D,0x0E,0x00};
static const uint8_t BMW_10B_0[15] = {0xCD, 0x19, 0x94, 0x6D, 0xE0, 0x34, 0x78, 0xDB,
0x97, 0x43, 0x0F, 0xF6, 0xBA, 0x6E, 0x81};
static const uint8_t BMW_10B_1[15] = {0x01, 0x02, 0x33, 0x34, 0x05, 0x06, 0x07, 0x08,
0x09, 0x0A, 0x0B, 0x0C, 0x0D, 0x0E, 0x00};
static uint8_t BMW_10B_counter = 0;
static int16_t Battery_Current = 0;
@ -38,155 +53,141 @@ static uint16_t Battery_Status = 0;
static uint16_t DC_link = 0;
static int16_t Battery_Power = 0;
void update_values_i3_battery()
{ //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
void update_values_i3_battery() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
//Calculate the SOC% value to send to inverter
Calculated_SOC = (Display_SOC * 10); //Increase decimal amount
Calculated_SOC = LB_MIN_SOC + (LB_MAX_SOC - LB_MIN_SOC) * (Calculated_SOC - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
if (Calculated_SOC < 0)
{ //We are in the real SOC% range of 0-20%, always set SOC sent to inverter as 0%
Calculated_SOC = 0;
Calculated_SOC = (Display_SOC * 10); //Increase decimal amount
Calculated_SOC =
LB_MIN_SOC + (LB_MAX_SOC - LB_MIN_SOC) * (Calculated_SOC - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
if (Calculated_SOC < 0) { //We are in the real SOC% range of 0-20%, always set SOC sent to inverter as 0%
Calculated_SOC = 0;
}
if (Calculated_SOC > 1000)
{ //We are in the real SOC% range of 80-100%, always set SOC sent to inverter as 100%
Calculated_SOC = 1000;
if (Calculated_SOC > 1000) { //We are in the real SOC% range of 80-100%, always set SOC sent to inverter as 100%
Calculated_SOC = 1000;
}
SOC = (Calculated_SOC * 10); //increase LB_SOC range from 0-100.0 -> 100.00
SOC = (Calculated_SOC * 10); //increase LB_SOC range from 0-100.0 -> 100.00
battery_voltage = Battery_Volts; //Unit V+1 (5000 = 500.0V)
battery_voltage = Battery_Volts; //Unit V+1 (5000 = 500.0V)
battery_current = Battery_Current;
battery_current = Battery_Current;
capacity_Wh = BATTERY_WH_MAX;
capacity_Wh = BATTERY_WH_MAX;
remaining_capacity_Wh = (Battery_Capacity_kWh * 1000);
remaining_capacity_Wh = (Battery_Capacity_kWh * 1000);
if(SOC > 9900) //If Soc is over 99%, stop charging
if (SOC > 9900) //If Soc is over 99%, stop charging
{
max_target_charge_power = 0;
}
else
{
max_target_charge_power = 5000; //Hardcoded value for testing. TODO, read real value from battery when discovered
} else {
max_target_charge_power = 5000; //Hardcoded value for testing. TODO, read real value from battery when discovered
}
if(SOC < 500) //If Soc is under 5%, stop dicharging
if (SOC < 500) //If Soc is under 5%, stop dicharging
{
max_target_discharge_power = 0;
}
else
{
max_target_discharge_power = 5000; //Hardcoded value for testing. TODO, read real value from battery when discovered
} else {
max_target_discharge_power =
5000; //Hardcoded value for testing. TODO, read real value from battery when discovered
}
Battery_Power = (Battery_Current * (Battery_Volts/10));
Battery_Power = (Battery_Current * (Battery_Volts / 10));
stat_batt_power = Battery_Power; //TODO, is mapping OK?
stat_batt_power = Battery_Power; //TODO, is mapping OK?
temperature_min; //hardcoded to 5*C in startup, TODO, find from battery CAN later
temperature_max; //hardcoded to 6*C in startup, TODO, find from battery CAN later
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if(!CANstillAlive)
{
temperature_min; //hardcoded to 5*C in startup, TODO, find from battery CAN later
temperature_max; //hardcoded to 6*C in startup, TODO, find from battery CAN later
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if (!CANstillAlive) {
bms_status = FAULT;
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
}
else
{
CANstillAlive--;
}
} else {
CANstillAlive--;
}
#ifdef DEBUG_VIA_USB
Serial.print("SOC% battery: ");
Serial.print(Display_SOC);
Serial.print(" SOC% sent to inverter: ");
Serial.print(SOC);
Serial.print(" Battery voltage: ");
Serial.print(battery_voltage);
Serial.print(" Remaining Wh: ");
Serial.print(remaining_capacity_Wh);
Serial.print(" Max charge power: ");
Serial.print(max_target_charge_power);
Serial.print(" Max discharge power: ");
Serial.print(max_target_discharge_power);
#endif
#ifdef DEBUG_VIA_USB
Serial.print("SOC% battery: ");
Serial.print(Display_SOC);
Serial.print(" SOC% sent to inverter: ");
Serial.print(SOC);
Serial.print(" Battery voltage: ");
Serial.print(battery_voltage);
Serial.print(" Remaining Wh: ");
Serial.print(remaining_capacity_Wh);
Serial.print(" Max charge power: ");
Serial.print(max_target_charge_power);
Serial.print(" Max discharge power: ");
Serial.print(max_target_discharge_power);
#endif
}
void receive_can_i3_battery(CAN_frame_t rx_frame)
{
CANstillAlive = 12;
switch (rx_frame.MsgID)
{
case 0x431: //Battery capacity [200ms]
Battery_Capacity_kWh = (((rx_frame.data.u8[1] & 0x0F) << 8 | rx_frame.data.u8[5])) / 50;
break;
case 0x432: //SOC% charged [200ms]
Voltage_Setpoint = ((rx_frame.data.u8[1] << 4 | rx_frame.data.u8[0] >> 4)) / 10;
Low_SOC = (rx_frame.data.u8[2] / 2);
High_SOC = (rx_frame.data.u8[3] / 2);
Display_SOC = (rx_frame.data.u8[4] / 2);
break;
case 0x112: //BMS status [10ms]
CANstillAlive = 12;
Battery_Current = ((rx_frame.data.u8[1] << 8 | rx_frame.data.u8[0]) / 10) - 819; //Amps
Battery_Volts = (rx_frame.data.u8[3] << 8 | rx_frame.data.u8[2]); //500.0 V
HVBatt_SOC = ((rx_frame.data.u8[5] & 0x0F) << 4 | rx_frame.data.u8[4]) / 10;
Battery_Status = (rx_frame.data.u8[6] & 0x0F);
DC_link = rx_frame.data.u8[7];
break;
case 0x430:
break;
case 0x1FA:
break;
case 0x40D:
break;
case 0x2FF:
break;
case 0x239:
break;
case 0x2BD:
break;
case 0x2F5:
break;
case 0x3EB:
break;
case 0x363:
break;
case 0x507:
break;
case 0x41C:
break;
default:
break;
}
void receive_can_i3_battery(CAN_frame_t rx_frame) {
CANstillAlive = 12;
switch (rx_frame.MsgID) {
case 0x431: //Battery capacity [200ms]
Battery_Capacity_kWh = (((rx_frame.data.u8[1] & 0x0F) << 8 | rx_frame.data.u8[5])) / 50;
break;
case 0x432: //SOC% charged [200ms]
Voltage_Setpoint = ((rx_frame.data.u8[1] << 4 | rx_frame.data.u8[0] >> 4)) / 10;
Low_SOC = (rx_frame.data.u8[2] / 2);
High_SOC = (rx_frame.data.u8[3] / 2);
Display_SOC = (rx_frame.data.u8[4] / 2);
break;
case 0x112: //BMS status [10ms]
CANstillAlive = 12;
Battery_Current = ((rx_frame.data.u8[1] << 8 | rx_frame.data.u8[0]) / 10) - 819; //Amps
Battery_Volts = (rx_frame.data.u8[3] << 8 | rx_frame.data.u8[2]); //500.0 V
HVBatt_SOC = ((rx_frame.data.u8[5] & 0x0F) << 4 | rx_frame.data.u8[4]) / 10;
Battery_Status = (rx_frame.data.u8[6] & 0x0F);
DC_link = rx_frame.data.u8[7];
break;
case 0x430:
break;
case 0x1FA:
break;
case 0x40D:
break;
case 0x2FF:
break;
case 0x239:
break;
case 0x2BD:
break;
case 0x2F5:
break;
case 0x3EB:
break;
case 0x363:
break;
case 0x507:
break;
case 0x41C:
break;
default:
break;
}
}
void send_can_i3_battery()
{
void send_can_i3_battery() {
unsigned long currentMillis = millis();
// Send 600ms CAN Message
if (currentMillis - previousMillis600 >= interval600)
{
previousMillis600 = currentMillis;
ESP32Can.CANWriteFrame(&BMW_512);
}
//Send 20ms message
if (currentMillis - previousMillis20 >= interval20)
{
previousMillis20 = currentMillis;
BMW_10B.data.u8[0] = BMW_10B_0[BMW_10B_counter];
BMW_10B.data.u8[1] = BMW_10B_1[BMW_10B_counter];
BMW_10B_counter++;
if(BMW_10B_counter > 14)
{
BMW_10B_counter = 0;
}
ESP32Can.CANWriteFrame(&BMW_10B);
}
// Send 600ms CAN Message
if (currentMillis - previousMillis600 >= interval600) {
previousMillis600 = currentMillis;
ESP32Can.CANWriteFrame(&BMW_512);
}
//Send 20ms message
if (currentMillis - previousMillis20 >= interval20) {
previousMillis20 = currentMillis;
BMW_10B.data.u8[0] = BMW_10B_0[BMW_10B_counter];
BMW_10B.data.u8[1] = BMW_10B_1[BMW_10B_counter];
BMW_10B_counter++;
if (BMW_10B_counter > 14) {
BMW_10B_counter = 0;
}
ESP32Can.CANWriteFrame(&BMW_10B);
}
}

View file

@ -1,11 +1,12 @@
#ifndef BMW_I3_BATTERY_H
#define BMW_I3_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped for the inverter
extern uint16_t SOC;
@ -35,4 +36,4 @@ void update_values_i3_battery();
void receive_can_i3_battery(CAN_frame_t rx_frame);
void send_can_i3_battery();
#endif
#endif

View file

@ -3,18 +3,48 @@
#include "../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
/* Do not change code below unless you are sure what you are doing */
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
static const int interval100 = 100; // interval (ms) at which send CAN Messages
const int rx_queue_size = 10; // Receive Queue size
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
static const int interval100 = 100; // interval (ms) at which send CAN Messages
const int rx_queue_size = 10; // Receive Queue size
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
CAN_frame_t CHADEMO_108 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x108,.data = {0x01, 0xF4, 0x01, 0x0F, 0xB3, 0x01, 0x00, 0x00}};
CAN_frame_t CHADEMO_109 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x109,.data = {0x02, 0x00, 0x00, 0x00, 0x01, 0x20, 0xFF, 0xFF}};
CAN_frame_t CHADEMO_108 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x108,
.data = {0x01, 0xF4, 0x01, 0x0F, 0xB3, 0x01, 0x00, 0x00}};
CAN_frame_t CHADEMO_109 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x109,
.data = {0x02, 0x00, 0x00, 0x00, 0x01, 0x20, 0xFF, 0xFF}};
//For chademo v2.0 only
CAN_frame_t CHADEMO_118 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x118,.data = {0x10, 0x64, 0x00, 0xB0, 0x00, 0x1E, 0x00, 0x8F}};
CAN_frame_t CHADEMO_208 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x208,.data = {0xFF, 0xF4, 0x01, 0xF0, 0x00, 0x00, 0xFA, 0x00}};
CAN_frame_t CHADEMO_209 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x209,.data = {0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t CHADEMO_118 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x118,
.data = {0x10, 0x64, 0x00, 0xB0, 0x00, 0x1E, 0x00, 0x8F}};
CAN_frame_t CHADEMO_208 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x208,
.data = {0xFF, 0xF4, 0x01, 0xF0, 0x00, 0x00, 0xFA, 0x00}};
CAN_frame_t CHADEMO_209 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x209,
.data = {0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
//H100
uint8_t MinimumChargeCurrent = 0;
@ -58,144 +88,133 @@ uint8_t DynamicControlStatus = 0;
uint8_t HighCurrentControlStatus = 0;
uint8_t HighVoltageControlStatus = 0;
void update_values_chademo_battery() { //This function maps all the values fetched via CAN to the correct parameters used for the inverter
bms_status = ACTIVE; //Startout in active mode
void update_values_chademo_battery()
{ //This function maps all the values fetched via CAN to the correct parameters used for the inverter
bms_status = ACTIVE; //Startout in active mode
SOC = ChargingRate;
max_target_discharge_power = (MaximumDischargeCurrent*MaximumBatteryVoltage); //In Watts, Convert A to P
max_target_discharge_power = (MaximumDischargeCurrent * MaximumBatteryVoltage); //In Watts, Convert A to P
battery_voltage = TargetBatteryVoltage; //Todo, scaling?
battery_voltage = TargetBatteryVoltage; //Todo, scaling?
capacity_Wh = ((RatedBatteryCapacity/0.11)*1000); //(Added in CHAdeMO v1.0.1), maybe handle hardcoded on lower protocol version?
capacity_Wh = ((RatedBatteryCapacity / 0.11) *
1000); //(Added in CHAdeMO v1.0.1), maybe handle hardcoded on lower protocol version?
remaining_capacity_Wh = (SOC/100)*capacity_Wh;
remaining_capacity_Wh = (SOC / 100) * capacity_Wh;
/* Check if the Vehicle is still sending CAN messages. If we go 60s without messages we raise an error*/
if(!CANstillAlive)
{
if (!CANstillAlive) {
bms_status = FAULT;
errorCode = 7;
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
}
else
{
} else {
CANstillAlive--;
}
#ifdef DEBUG_VIA_USB
if(errorCode > 0)
{
Serial.print("ERROR CODE ACTIVE IN SYSTEM. NUMBER: ");
Serial.println(errorCode);
}
Serial.print("BMS Status (3=OK): ");
Serial.println(bms_status);
switch (bms_char_dis_status)
{
case 0:
Serial.println("Battery Idle");
break;
case 1:
Serial.println("Battery Discharging");
break;
case 2:
Serial.println("Battery Charging");
break;
default:
break;
}
Serial.print("Max discharge power: ");
Serial.println(max_target_discharge_power);
Serial.print("Max charge power: ");
Serial.println(max_target_charge_power);
Serial.print("SOH%: ");
Serial.println(StateOfHealth);
Serial.print("SOC% to Inverter: ");
Serial.println(SOC);
Serial.print("Temperature Min: ");
Serial.println(temperature_min);
Serial.print("Temperature Max: ");
Serial.println(temperature_max);
#endif
#ifdef DEBUG_VIA_USB
if (errorCode > 0) {
Serial.print("ERROR CODE ACTIVE IN SYSTEM. NUMBER: ");
Serial.println(errorCode);
}
Serial.print("BMS Status (3=OK): ");
Serial.println(bms_status);
switch (bms_char_dis_status) {
case 0:
Serial.println("Battery Idle");
break;
case 1:
Serial.println("Battery Discharging");
break;
case 2:
Serial.println("Battery Charging");
break;
default:
break;
}
Serial.print("Max discharge power: ");
Serial.println(max_target_discharge_power);
Serial.print("Max charge power: ");
Serial.println(max_target_charge_power);
Serial.print("SOH%: ");
Serial.println(StateOfHealth);
Serial.print("SOC% to Inverter: ");
Serial.println(SOC);
Serial.print("Temperature Min: ");
Serial.println(temperature_min);
Serial.print("Temperature Max: ");
Serial.println(temperature_max);
#endif
}
void receive_can_chademo_battery(CAN_frame_t rx_frame)
{
CANstillAlive == 12; //We are getting CAN messages from the vehicle, inform the watchdog
void receive_can_chademo_battery(CAN_frame_t rx_frame) {
CANstillAlive == 12; //We are getting CAN messages from the vehicle, inform the watchdog
switch (rx_frame.MsgID)
{
case 0x100:
MinimumChargeCurrent = rx_frame.data.u8[0];
MinumumBatteryVoltage = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
MaximumBatteryVoltage = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
ConstantOfChargingRateIndication = rx_frame.data.u8[6];
break;
case 0x101:
MaxChargingTime10sBit = rx_frame.data.u8[1];
MaxChargingTime1minBit = rx_frame.data.u8[2];
EstimatedChargingTime = rx_frame.data.u8[3];
RatedBatteryCapacity = ((rx_frame.data.u8[5] << 8) | rx_frame.data.u8[6]);
break;
case 0x102:
ControlProtocolNumberEV = rx_frame.data.u8[0];
TargetBatteryVoltage = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[2]);
ChargingCurrentRequest = rx_frame.data.u8[3];
FaultBatteryOvervoltage = (rx_frame.data.u8[4] & 0x01);
FaultBatteryUndervoltage = (rx_frame.data.u8[4] & 0x02) >> 1;
FaultBatteryCurrentDeviation = (rx_frame.data.u8[4] & 0x04) >> 2;
FaultHighBatteryTemperature = (rx_frame.data.u8[4] & 0x08) >> 3;
FaultBatteryVoltageDeviation = (rx_frame.data.u8[4] & 0x10) >> 4;
StatusVehicleCharging = (rx_frame.data.u8[5] & 0x01);
StatusVehicleShifterPosition = (rx_frame.data.u8[5] & 0x02) >> 1;
StatusChargingSystem = (rx_frame.data.u8[5] & 0x04) >> 2;
StatusVehicle = (rx_frame.data.u8[5] & 0x08) >> 3;
StatusNormalStopRequest = (rx_frame.data.u8[5] & 0x10) >> 4;
ChargingRate = rx_frame.data.u8[6];
break;
case 0x200: //For V2X
MaximumDischargeCurrent = rx_frame.data.u8[0];
MinimumDischargeVoltage = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
MinimumBatteryDischargeLevel = rx_frame.data.u8[6];
MaxRemainingCapacityForCharging = rx_frame.data.u8[7];
break;
case 0x201: //For V2X
V2HchargeDischargeSequenceNum = rx_frame.data.u8[0];
ApproxDischargeCompletionTime = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[2]);
AvailableVehicleEnergy = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[4]);
break;
case 0x700:
AutomakerCode = rx_frame.data.u8[0];
OptionalContent = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[2]); //Actually more bytes, but not needed for our purpose
break;
case 0x110: //Only present on Chademo v2.0
DynamicControlStatus = (rx_frame.data.u8[0] & 0x01);
HighCurrentControlStatus = (rx_frame.data.u8[0] & 0x02) >> 1;
HighVoltageControlStatus = (rx_frame.data.u8[0] & 0x04) >> 2;
default:
break;
}
switch (rx_frame.MsgID) {
case 0x100:
MinimumChargeCurrent = rx_frame.data.u8[0];
MinumumBatteryVoltage = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
MaximumBatteryVoltage = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
ConstantOfChargingRateIndication = rx_frame.data.u8[6];
break;
case 0x101:
MaxChargingTime10sBit = rx_frame.data.u8[1];
MaxChargingTime1minBit = rx_frame.data.u8[2];
EstimatedChargingTime = rx_frame.data.u8[3];
RatedBatteryCapacity = ((rx_frame.data.u8[5] << 8) | rx_frame.data.u8[6]);
break;
case 0x102:
ControlProtocolNumberEV = rx_frame.data.u8[0];
TargetBatteryVoltage = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[2]);
ChargingCurrentRequest = rx_frame.data.u8[3];
FaultBatteryOvervoltage = (rx_frame.data.u8[4] & 0x01);
FaultBatteryUndervoltage = (rx_frame.data.u8[4] & 0x02) >> 1;
FaultBatteryCurrentDeviation = (rx_frame.data.u8[4] & 0x04) >> 2;
FaultHighBatteryTemperature = (rx_frame.data.u8[4] & 0x08) >> 3;
FaultBatteryVoltageDeviation = (rx_frame.data.u8[4] & 0x10) >> 4;
StatusVehicleCharging = (rx_frame.data.u8[5] & 0x01);
StatusVehicleShifterPosition = (rx_frame.data.u8[5] & 0x02) >> 1;
StatusChargingSystem = (rx_frame.data.u8[5] & 0x04) >> 2;
StatusVehicle = (rx_frame.data.u8[5] & 0x08) >> 3;
StatusNormalStopRequest = (rx_frame.data.u8[5] & 0x10) >> 4;
ChargingRate = rx_frame.data.u8[6];
break;
case 0x200: //For V2X
MaximumDischargeCurrent = rx_frame.data.u8[0];
MinimumDischargeVoltage = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
MinimumBatteryDischargeLevel = rx_frame.data.u8[6];
MaxRemainingCapacityForCharging = rx_frame.data.u8[7];
break;
case 0x201: //For V2X
V2HchargeDischargeSequenceNum = rx_frame.data.u8[0];
ApproxDischargeCompletionTime = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[2]);
AvailableVehicleEnergy = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[4]);
break;
case 0x700:
AutomakerCode = rx_frame.data.u8[0];
OptionalContent =
((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[2]); //Actually more bytes, but not needed for our purpose
break;
case 0x110: //Only present on Chademo v2.0
DynamicControlStatus = (rx_frame.data.u8[0] & 0x01);
HighCurrentControlStatus = (rx_frame.data.u8[0] & 0x02) >> 1;
HighVoltageControlStatus = (rx_frame.data.u8[0] & 0x04) >> 2;
default:
break;
}
}
void send_can_chademo_battery()
{
void send_can_chademo_battery() {
unsigned long currentMillis = millis();
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100)
{
previousMillis100 = currentMillis;
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100) {
previousMillis100 = currentMillis;
ESP32Can.CANWriteFrame(&CHADEMO_108);
ESP32Can.CANWriteFrame(&CHADEMO_108);
ESP32Can.CANWriteFrame(&CHADEMO_109);
ESP32Can.CANWriteFrame(&CHADEMO_208);
ESP32Can.CANWriteFrame(&CHADEMO_209);
if(ControlProtocolNumberEV >= 0x03)
{ //Only send the following on Chademo 2.0 vehicles?
if (ControlProtocolNumberEV >= 0x03) { //Only send the following on Chademo 2.0 vehicles?
ESP32Can.CANWriteFrame(&CHADEMO_118);
}
}
}
}

View file

@ -1,11 +1,12 @@
#ifndef CHADEMO_BATTERY_H
#define CHADEMO_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped
extern uint16_t SOC;
@ -34,4 +35,4 @@ void update_values_chademo_battery();
void receive_can_chademo_battery(CAN_frame_t rx_frame);
void send_can_chademo_battery();
#endif
#endif

View file

@ -6,17 +6,17 @@
//Figure out if CAN messages need to be sent to keep the system happy?
/* Do not change code below unless you are sure what you are doing */
#define BMU_MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to inverter
#define BMU_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to inverter
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
#define BMU_MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to inverter
#define BMU_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to inverter
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
static uint8_t BMU_Detected = 0;
static uint8_t CMU_Detected = 0;
static unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was sent
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was sent
static const int interval10 = 10; // interval (ms) at which send CAN Messages
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was sent
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was sent
static const int interval10 = 10; // interval (ms) at which send CAN Messages
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static int pid_index = 0;
static int cmu_id = 0;
@ -32,211 +32,196 @@ static double voltage2 = 0;
static double BMU_Current = 0;
static double BMU_PackVoltage = 0;
static double BMU_Power = 0;
static double cell_voltages[89]; //array with all the cellvoltages //Todo, what is max array size? 80/88 cells?
static double cell_temperatures[89]; //array with all the celltemperatures //Todo, what is max array size? 80/88cells?
static double cell_voltages[89]; //array with all the cellvoltages //Todo, what is max array size? 80/88 cells?
static double cell_temperatures[89]; //array with all the celltemperatures //Todo, what is max array size? 80/88cells?
static double max_volt_cel = 3.70;
static double min_volt_cel = 3.70;
static double max_temp_cel = 20.00;
static double min_temp_cel = 19.00;
void update_values_imiev_battery() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
void update_values_imiev_battery()
{ //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
SOC = (uint16_t)(BMU_SOC * 100); //increase BMU_SOC range from 0-100 -> 100.00
SOC = (uint16_t)(BMU_SOC * 100); //increase BMU_SOC range from 0-100 -> 100.00
battery_voltage = (uint16_t)(BMU_PackVoltage * 10); // Multiply by 10 and cast to uint16_t
battery_voltage = (uint16_t)(BMU_PackVoltage * 10); // Multiply by 10 and cast to uint16_t
battery_current = (BMU_Current * 10); //Todo, scaling?
battery_current = (BMU_Current*10); //Todo, scaling?
capacity_Wh = BATTERY_WH_MAX; //Hardcoded to header value
capacity_Wh = BATTERY_WH_MAX; //Hardcoded to header value
remaining_capacity_Wh = (uint16_t)((SOC/10000)*capacity_Wh);
remaining_capacity_Wh = (uint16_t)((SOC / 10000) * capacity_Wh);
//We do not know if the max charge power is sent by the battery. So we estimate the value based on SOC%
if(SOC == 10000){ //100.00%
max_target_charge_power = 0; //When battery is 100% full, set allowed charge W to 0
}
else{
max_target_charge_power = 10000; //Otherwise we can push 10kW into the pack!
if (SOC == 10000) { //100.00%
max_target_charge_power = 0; //When battery is 100% full, set allowed charge W to 0
} else {
max_target_charge_power = 10000; //Otherwise we can push 10kW into the pack!
}
if(SOC < 200){ //2.00%
max_target_discharge_power = 0; //When battery is empty (below 2%), set allowed discharge W to 0
}
else{
max_target_discharge_power = 10000; //Otherwise we can discharge 10kW from the pack!
if (SOC < 200) { //2.00%
max_target_discharge_power = 0; //When battery is empty (below 2%), set allowed discharge W to 0
} else {
max_target_discharge_power = 10000; //Otherwise we can discharge 10kW from the pack!
}
stat_batt_power = BMU_Power; //TODO, Scaling?
stat_batt_power = BMU_Power; //TODO, Scaling?
static int n = sizeof(cell_voltages) / sizeof(cell_voltages[0]);
max_volt_cel = cell_voltages[0]; // Initialize max with the first element of the array
for (int i = 1; i < n; i++) {
if (cell_voltages[i] > max_volt_cel) {
max_volt_cel = cell_voltages[i]; // Update max if we find a larger element
}
max_volt_cel = cell_voltages[0]; // Initialize max with the first element of the array
for (int i = 1; i < n; i++) {
if (cell_voltages[i] > max_volt_cel) {
max_volt_cel = cell_voltages[i]; // Update max if we find a larger element
}
}
min_volt_cel = cell_voltages[0]; // Initialize min with the first element of the array
for (int i = 1; i < n; i++) {
if (cell_voltages[i] < min_volt_cel) {
min_volt_cel = cell_voltages[i]; // Update min if we find a smaller element
}
min_volt_cel = cell_voltages[0]; // Initialize min with the first element of the array
for (int i = 1; i < n; i++) {
if (cell_voltages[i] < min_volt_cel) {
min_volt_cel = cell_voltages[i]; // Update min if we find a smaller element
}
}
static int m = sizeof(cell_voltages) / sizeof(cell_temperatures[0]);
max_temp_cel = cell_temperatures[0]; // Initialize max with the first element of the array
for (int i = 1; i < m; i++) {
if (cell_temperatures[i] > max_temp_cel) {
max_temp_cel = cell_temperatures[i]; // Update max if we find a larger element
}
max_temp_cel = cell_temperatures[0]; // Initialize max with the first element of the array
for (int i = 1; i < m; i++) {
if (cell_temperatures[i] > max_temp_cel) {
max_temp_cel = cell_temperatures[i]; // Update max if we find a larger element
}
}
min_temp_cel = cell_temperatures[0]; // Initialize min with the first element of the array
for (int i = 1; i < m; i++) {
if (cell_temperatures[i] < min_temp_cel) {
if(min_temp_cel != -50.00){ //-50.00 means this sensor not connected
min_temp_cel = cell_temperatures[i]; // Update max if we find a smaller element
}
min_temp_cel = cell_temperatures[0]; // Initialize min with the first element of the array
for (int i = 1; i < m; i++) {
if (cell_temperatures[i] < min_temp_cel) {
if (min_temp_cel != -50.00) { //-50.00 means this sensor not connected
min_temp_cel = cell_temperatures[i]; // Update max if we find a smaller element
}
}
}
cell_max_voltage = (uint16_t)(max_volt_cel*1000);
cell_min_voltage = (uint16_t)(min_volt_cel*1000);
cell_max_voltage = (uint16_t)(max_volt_cel * 1000);
temperature_min = (uint16_t)(min_temp_cel*1000);
cell_min_voltage = (uint16_t)(min_volt_cel * 1000);
temperature_max = (uint16_t)(max_temp_cel*1000);
temperature_min = (uint16_t)(min_temp_cel * 1000);
temperature_max = (uint16_t)(max_temp_cel * 1000);
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if(!CANstillAlive)
{
if (!CANstillAlive) {
bms_status = FAULT;
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
}
else
{
} else {
CANstillAlive--;
}
if(!BMU_Detected){
if (!BMU_Detected) {
Serial.println("BMU not detected, check wiring!");
}
#ifdef DEBUG_VIA_USB
Serial.println("Battery Values");
Serial.print("BMU SOC: ");
Serial.print(BMU_SOC);
Serial.print(" BMU Current: ");
Serial.print(BMU_Current);
Serial.print(" BMU Battery Voltage: ");
Serial.print(BMU_PackVoltage);
Serial.print(" BMU_Power: ");
Serial.print(BMU_Power);
Serial.print(" Cell max voltage: ");
Serial.print(max_volt_cel);
Serial.print(" Cell min voltage: ");
Serial.print(min_volt_cel);
Serial.print(" Cell max temp: ");
Serial.print(max_temp_cel);
Serial.print(" Cell min temp: ");
Serial.println(min_temp_cel);
Serial.println("Values sent to inverter");
Serial.print("SOC% (0-100.00): ");
Serial.print(SOC);
Serial.print(" Voltage (0-400.0): ");
Serial.print(battery_voltage);
Serial.print(" Capacity WH full (0-60000): ");
Serial.print(capacity_Wh);
Serial.print(" Capacity WH remain (0-60000): ");
Serial.print(remaining_capacity_Wh);
Serial.print(" Max charge power W (0-10000): ");
Serial.print(max_target_charge_power);
Serial.print(" Max discharge power W (0-10000): ");
Serial.print(max_target_discharge_power);
Serial.print(" Temp max ");
Serial.print(temperature_max);
Serial.print(" Temp min ");
Serial.print(temperature_min);
Serial.print(" Cell mV max ");
Serial.print(cell_max_voltage);
Serial.print(" Cell mV min ");
Serial.print(cell_min_voltage);
#endif
#ifdef DEBUG_VIA_USB
Serial.println("Battery Values");
Serial.print("BMU SOC: ");
Serial.print(BMU_SOC);
Serial.print(" BMU Current: ");
Serial.print(BMU_Current);
Serial.print(" BMU Battery Voltage: ");
Serial.print(BMU_PackVoltage);
Serial.print(" BMU_Power: ");
Serial.print(BMU_Power);
Serial.print(" Cell max voltage: ");
Serial.print(max_volt_cel);
Serial.print(" Cell min voltage: ");
Serial.print(min_volt_cel);
Serial.print(" Cell max temp: ");
Serial.print(max_temp_cel);
Serial.print(" Cell min temp: ");
Serial.println(min_temp_cel);
Serial.println("Values sent to inverter");
Serial.print("SOC% (0-100.00): ");
Serial.print(SOC);
Serial.print(" Voltage (0-400.0): ");
Serial.print(battery_voltage);
Serial.print(" Capacity WH full (0-60000): ");
Serial.print(capacity_Wh);
Serial.print(" Capacity WH remain (0-60000): ");
Serial.print(remaining_capacity_Wh);
Serial.print(" Max charge power W (0-10000): ");
Serial.print(max_target_charge_power);
Serial.print(" Max discharge power W (0-10000): ");
Serial.print(max_target_discharge_power);
Serial.print(" Temp max ");
Serial.print(temperature_max);
Serial.print(" Temp min ");
Serial.print(temperature_min);
Serial.print(" Cell mV max ");
Serial.print(cell_max_voltage);
Serial.print(" Cell mV min ");
Serial.print(cell_min_voltage);
#endif
}
void receive_can_imiev_battery(CAN_frame_t rx_frame)
{
CANstillAlive = 12; //Todo, move this inside a known message ID to prevent CAN inverter from keeping battery alive detection going
switch (rx_frame.MsgID)
{
case 0x374: //BMU message, 10ms - SOC
temp_value = ((rx_frame.data.u8[1] - 10) / 2);
if(temp_value >= 0 && temp_value <= 101){
BMU_SOC = temp_value;
}
break;
case 0x373: //BMU message, 100ms - Pack Voltage and current
BMU_Current = ((((((rx_frame.data.u8[2] * 256.0) + rx_frame.data.u8[3])) - 32768)) * 0.01);
BMU_PackVoltage = ((rx_frame.data.u8[4] * 256.0 + rx_frame.data.u8[5]) * 0.1);
BMU_Power = (BMU_Current * BMU_PackVoltage);
break;
case 0x6e1: //BMU message, 25ms - Battery temperatures and voltages
case 0x6e2:
case 0x6e3:
case 0x6e4:
BMU_Detected = 1;
//Pid index 0-3
pid_index = (rx_frame.MsgID) - 1761;
//cmu index 1-12: ignore high order nibble which appears to sometimes contain other status bits
cmu_id = (rx_frame.data.u8[0] & 0x0f);
//
temp1 = rx_frame.data.u8[1] - 50.0;
temp2 = rx_frame.data.u8[2] - 50.0;
temp3 = rx_frame.data.u8[3] - 50.0;
voltage1 = (((rx_frame.data.u8[4] * 256.0 + rx_frame.data.u8[5]) * 0.005) + 2.1);
voltage2 = (((rx_frame.data.u8[6] * 256.0 + rx_frame.data.u8[7]) * 0.005) + 2.1);
voltage_index = ((cmu_id - 1) * 8 + (2 * pid_index));
temp_index = ((cmu_id - 1) * 6 + (2 * pid_index));
if (cmu_id >= 7)
{
voltage_index -= 4;
temp_index -= 3;
}
cell_voltages[voltage_index] = voltage1;
cell_voltages[voltage_index + 1] = voltage2;
if (pid_index == 0)
{
cell_temperatures[temp_index] = temp2;
cell_temperatures[temp_index + 1] = temp3;
}
else
{
cell_temperatures[temp_index] = temp1;
if (cmu_id != 6 && cmu_id != 12)
{
cell_temperatures[temp_index + 1] = temp2;
void receive_can_imiev_battery(CAN_frame_t rx_frame) {
CANstillAlive =
12; //Todo, move this inside a known message ID to prevent CAN inverter from keeping battery alive detection going
switch (rx_frame.MsgID) {
case 0x374: //BMU message, 10ms - SOC
temp_value = ((rx_frame.data.u8[1] - 10) / 2);
if (temp_value >= 0 && temp_value <= 101) {
BMU_SOC = temp_value;
}
}
break;
default:
break;
break;
case 0x373: //BMU message, 100ms - Pack Voltage and current
BMU_Current = ((((((rx_frame.data.u8[2] * 256.0) + rx_frame.data.u8[3])) - 32768)) * 0.01);
BMU_PackVoltage = ((rx_frame.data.u8[4] * 256.0 + rx_frame.data.u8[5]) * 0.1);
BMU_Power = (BMU_Current * BMU_PackVoltage);
break;
case 0x6e1: //BMU message, 25ms - Battery temperatures and voltages
case 0x6e2:
case 0x6e3:
case 0x6e4:
BMU_Detected = 1;
//Pid index 0-3
pid_index = (rx_frame.MsgID) - 1761;
//cmu index 1-12: ignore high order nibble which appears to sometimes contain other status bits
cmu_id = (rx_frame.data.u8[0] & 0x0f);
//
temp1 = rx_frame.data.u8[1] - 50.0;
temp2 = rx_frame.data.u8[2] - 50.0;
temp3 = rx_frame.data.u8[3] - 50.0;
voltage1 = (((rx_frame.data.u8[4] * 256.0 + rx_frame.data.u8[5]) * 0.005) + 2.1);
voltage2 = (((rx_frame.data.u8[6] * 256.0 + rx_frame.data.u8[7]) * 0.005) + 2.1);
voltage_index = ((cmu_id - 1) * 8 + (2 * pid_index));
temp_index = ((cmu_id - 1) * 6 + (2 * pid_index));
if (cmu_id >= 7) {
voltage_index -= 4;
temp_index -= 3;
}
cell_voltages[voltage_index] = voltage1;
cell_voltages[voltage_index + 1] = voltage2;
if (pid_index == 0) {
cell_temperatures[temp_index] = temp2;
cell_temperatures[temp_index + 1] = temp3;
} else {
cell_temperatures[temp_index] = temp1;
if (cmu_id != 6 && cmu_id != 12) {
cell_temperatures[temp_index + 1] = temp2;
}
}
break;
default:
break;
}
}
void send_can_imiev_battery()
{
void send_can_imiev_battery() {
unsigned long currentMillis = millis();
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100)
{
previousMillis100 = currentMillis;
if (currentMillis - previousMillis100 >= interval100) {
previousMillis100 = currentMillis;
}
}

View file

@ -1,11 +1,12 @@
#ifndef IMIEV_CZERO_ION_BATTERY_H
#define IMIEV_CZERO_ION_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped for the Gen24
extern uint16_t SOC;
@ -38,4 +39,4 @@ void update_values_imiev_battery();
void receive_can_imiev_battery(CAN_frame_t rx_frame);
void send_can_imiev_battery();
#endif
#endif

View file

@ -3,32 +3,31 @@
#include "../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
/* Do not change code below unless you are sure what you are doing */
static unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was send
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
static const int interval10 = 10; // interval (ms) at which send CAN Messages
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was send
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
static const int interval10 = 10; // interval (ms) at which send CAN Messages
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
#define LB_MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to Inverter
#define LB_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to Inverter
#define LB_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to Inverter
static int SOC_1 = 0;
static int SOC_2 = 0;
static int SOC_3 = 0;
void update_values_kiaHyundai_64_battery()
{ //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
void update_values_kiaHyundai_64_battery() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
SOC;
SOC;
battery_voltage;
battery_voltage;
battery_current;
battery_current;
capacity_Wh = BATTERY_WH_MAX;
capacity_Wh = BATTERY_WH_MAX;
remaining_capacity_Wh;
remaining_capacity_Wh;
max_target_discharge_power;
@ -36,99 +35,90 @@ void update_values_kiaHyundai_64_battery()
stat_batt_power;
temperature_min;
temperature_max;
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if(!CANstillAlive)
{
bms_status = FAULT;
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
}
else
{
CANstillAlive--;
}
temperature_min;
#ifdef DEBUG_VIA_USB
Serial.print("SOC% candidate 1: ");
Serial.println(SOC_1);
Serial.print("SOC% candidate 2: ");
Serial.println(SOC_2);
Serial.print("SOC% candidate 3: ");
Serial.println(SOC_3);
#endif
temperature_max;
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if (!CANstillAlive) {
bms_status = FAULT;
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
} else {
CANstillAlive--;
}
#ifdef DEBUG_VIA_USB
Serial.print("SOC% candidate 1: ");
Serial.println(SOC_1);
Serial.print("SOC% candidate 2: ");
Serial.println(SOC_2);
Serial.print("SOC% candidate 3: ");
Serial.println(SOC_3);
#endif
}
void receive_can_kiaHyundai_64_battery(CAN_frame_t rx_frame)
{
CANstillAlive = 12;
switch (rx_frame.MsgID)
{
case 0x3F6:
break;
case 0x491:
break;
case 0x493:
break;
case 0x497:
break;
case 0x498:
break;
case 0x4DD:
break;
case 0x4DE:
break;
case 0x4E2:
break;
case 0x542:
SOC_1 = rx_frame.data.u8[0];
break;
case 0x594:
SOC_2 = rx_frame.data.u8[5];
break;
case 0x595:
break;
case 0x596:
break;
case 0x597:
break;
case 0x598:
SOC_3 = (rx_frame.data.u8[4] * 256.0 + rx_frame.data.u8[5]);
break;
case 0x599:
break;
case 0x59C:
break;
case 0x59E:
break;
case 0x5A3:
break;
case 0x5D5:
break;
case 0x5D6:
break;
case 0x5D7:
break;
case 0x5D8:
break;
default:
break;
}
void receive_can_kiaHyundai_64_battery(CAN_frame_t rx_frame) {
CANstillAlive = 12;
switch (rx_frame.MsgID) {
case 0x3F6:
break;
case 0x491:
break;
case 0x493:
break;
case 0x497:
break;
case 0x498:
break;
case 0x4DD:
break;
case 0x4DE:
break;
case 0x4E2:
break;
case 0x542:
SOC_1 = rx_frame.data.u8[0];
break;
case 0x594:
SOC_2 = rx_frame.data.u8[5];
break;
case 0x595:
break;
case 0x596:
break;
case 0x597:
break;
case 0x598:
SOC_3 = (rx_frame.data.u8[4] * 256.0 + rx_frame.data.u8[5]);
break;
case 0x599:
break;
case 0x59C:
break;
case 0x59E:
break;
case 0x5A3:
break;
case 0x5D5:
break;
case 0x5D6:
break;
case 0x5D7:
break;
case 0x5D8:
break;
default:
break;
}
}
void send_can_kiaHyundai_64_battery()
{
void send_can_kiaHyundai_64_battery() {
unsigned long currentMillis = millis();
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100)
{
previousMillis100 = currentMillis;
}
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100) {
previousMillis100 = currentMillis;
}
//Send 10ms message
if (currentMillis - previousMillis10 >= interval10)
{
previousMillis10 = currentMillis;
}
if (currentMillis - previousMillis10 >= interval10) {
previousMillis10 = currentMillis;
}
}

View file

@ -1,11 +1,12 @@
#ifndef KIA_HYUNDAI_64_BATTERY_H
#define KIA_HYUNDAI_64_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped for the Gen24
extern uint16_t SOC;
@ -35,4 +36,4 @@ void update_values_kiaHyundai_64_battery();
void receive_can_kiaHyundai_64_battery(CAN_frame_t rx_frame);
void send_can_kiaHyundai_64_battery();
#endif
#endif

File diff suppressed because it is too large Load diff

View file

@ -1,30 +1,31 @@
#ifndef NISSAN_LEAF_BATTERY_H
#define NISSAN_LEAF_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped for the inverter
extern uint16_t SOC; //SOC%, 0-100.00 (0-10000)
extern uint16_t StateOfHealth; //SOH%, 0-100.00 (0-10000)
extern uint16_t battery_voltage; //V+1, 0-500.0 (0-5000)
extern uint16_t battery_current; //A+1, Goes thru convert2unsignedint16 function (5.0A = 50, -5.0A = 65485)
extern uint16_t capacity_Wh; //Wh, 0-60000
extern uint16_t remaining_capacity_Wh; //Wh, 0-60000
extern uint16_t max_target_discharge_power; //W, 0-60000
extern uint16_t max_target_charge_power; //W, 0-60000
extern uint16_t bms_status; //Enum, 0-5
extern uint16_t bms_char_dis_status; //Enum, 0-2
extern uint16_t stat_batt_power; //W, Goes thru convert2unsignedint16 function (5W = 5, -5W = 65530)
extern uint16_t temperature_min; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t temperature_max; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t cell_max_voltage; //mV, 0-4350
extern uint16_t cell_min_voltage; //mV, 0-4350
extern uint8_t batteryAllowsContactorClosing; //Bool, 1=true, 0=false
extern uint8_t LEDcolor; //Enum, 0-2
extern uint16_t SOC; //SOC%, 0-100.00 (0-10000)
extern uint16_t StateOfHealth; //SOH%, 0-100.00 (0-10000)
extern uint16_t battery_voltage; //V+1, 0-500.0 (0-5000)
extern uint16_t battery_current; //A+1, Goes thru convert2unsignedint16 function (5.0A = 50, -5.0A = 65485)
extern uint16_t capacity_Wh; //Wh, 0-60000
extern uint16_t remaining_capacity_Wh; //Wh, 0-60000
extern uint16_t max_target_discharge_power; //W, 0-60000
extern uint16_t max_target_charge_power; //W, 0-60000
extern uint16_t bms_status; //Enum, 0-5
extern uint16_t bms_char_dis_status; //Enum, 0-2
extern uint16_t stat_batt_power; //W, Goes thru convert2unsignedint16 function (5W = 5, -5W = 65530)
extern uint16_t temperature_min; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t temperature_max; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t cell_max_voltage; //mV, 0-4350
extern uint16_t cell_min_voltage; //mV, 0-4350
extern uint8_t batteryAllowsContactorClosing; //Bool, 1=true, 0=false
extern uint8_t LEDcolor; //Enum, 0-2
// Definitions for bms_status
#define STANDBY 0
#define INACTIVE 1
@ -44,4 +45,4 @@ uint16_t convert2unsignedint16(int16_t signed_value);
uint16_t Temp_fromRAW_to_F(uint16_t temperature);
bool is_message_corrupt(CAN_frame_t rx_frame);
#endif
#endif

View file

@ -3,11 +3,11 @@
#include "../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
/* Do not change code below unless you are sure what you are doing */
#define LB_MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to Fronius
#define LB_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to Fronius
const int rx_queue_size = 10; // Receive Queue size
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
#define LB_MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to Fronius
#define LB_MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to Fronius
const int rx_queue_size = 10; // Receive Queue size
static uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
static uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
static int16_t LB_SOC = 0;
static int16_t LB_SOH = 0;
static int16_t LB_MIN_TEMPERATURE = 0;
@ -17,149 +17,139 @@ static uint32_t LB_Discharge_Power_Limit_Watts = 0;
static uint16_t LB_Charge_Power_Limit = 0;
static uint32_t LB_Charge_Power_Limit_Watts = 0;
CAN_frame_t ZOE_423 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x423,
.data = {0x33, 0x00, 0xFF, 0xFF, 0x00, 0xE0, 0x00, 0x00}};
CAN_frame_t ZOE_423 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x423,.data = {0x33, 0x00, 0xFF, 0xFF, 0x00, 0xE0, 0x00, 0x00}};
static unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was sent
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was sent
static const int interval10 = 10; // interval (ms) at which send CAN Messages
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was sent
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was sent
static const int interval10 = 10; // interval (ms) at which send CAN Messages
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static int BMSPollCounter = 0;
void update_values_zoe_battery()
{ //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
StateOfHealth = (LB_SOH * 100); //Increase range from 99% -> 99.00%
void update_values_zoe_battery() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
bms_status = ACTIVE; //Startout in active mode
StateOfHealth = (LB_SOH * 100); //Increase range from 99% -> 99.00%
//Calculate the SOC% value to send to Fronius
LB_SOC = LB_MIN_SOC + (LB_MAX_SOC - LB_MIN_SOC) * (LB_SOC - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
if (LB_SOC < 0)
{ //We are in the real SOC% range of 0-20%, always set SOC sent to Fronius as 0%
LB_SOC = 0;
LB_SOC = LB_MIN_SOC + (LB_MAX_SOC - LB_MIN_SOC) * (LB_SOC - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
if (LB_SOC < 0) { //We are in the real SOC% range of 0-20%, always set SOC sent to Fronius as 0%
LB_SOC = 0;
}
if (LB_SOC > 1000)
{ //We are in the real SOC% range of 80-100%, always set SOC sent to Fronius as 100%
LB_SOC = 1000;
if (LB_SOC > 1000) { //We are in the real SOC% range of 80-100%, always set SOC sent to Fronius as 100%
LB_SOC = 1000;
}
SOC = (LB_SOC * 10); //increase LB_SOC range from 0-100.0 -> 100.00
SOC = (LB_SOC * 10); //increase LB_SOC range from 0-100.0 -> 100.00
battery_voltage;
battery_current;
capacity_Wh = BATTERY_WH_MAX;
remaining_capacity_Wh;
capacity_Wh = BATTERY_WH_MAX;
remaining_capacity_Wh;
LB_Discharge_Power_Limit_Watts = (LB_Discharge_Power_Limit * 500); //Convert value fetched from battery to watts
LB_Discharge_Power_Limit_Watts = (LB_Discharge_Power_Limit * 500); //Convert value fetched from battery to watts
/* Define power able to be discharged from battery */
if(LB_Discharge_Power_Limit_Watts > 30000) //if >30kW can be pulled from battery
{
max_target_discharge_power = 30000; //cap value so we don't go over the Fronius limits
}
else
if (LB_Discharge_Power_Limit_Watts > 30000) //if >30kW can be pulled from battery
{
max_target_discharge_power = 30000; //cap value so we don't go over the Fronius limits
} else {
max_target_discharge_power = LB_Discharge_Power_Limit_Watts;
}
if(SOC == 0) //Scaled SOC% value is 0.00%, we should not discharge battery further
if (SOC == 0) //Scaled SOC% value is 0.00%, we should not discharge battery further
{
max_target_discharge_power = 0;
}
LB_Charge_Power_Limit_Watts = (LB_Charge_Power_Limit * 500); //Convert value fetched from battery to watts
LB_Charge_Power_Limit_Watts = (LB_Charge_Power_Limit * 500); //Convert value fetched from battery to watts
/* Define power able to be put into the battery */
if(LB_Charge_Power_Limit_Watts > 30000) //if >30kW can be put into the battery
if (LB_Charge_Power_Limit_Watts > 30000) //if >30kW can be put into the battery
{
max_target_charge_power = 30000; //cap value so we don't go over the Fronius limits
max_target_charge_power = 30000; //cap value so we don't go over the Fronius limits
}
if(LB_Charge_Power_Limit_Watts < 0)
{
max_target_charge_power = 0; //cap calue so we dont do under the Fronius limits
}
else
{
if (LB_Charge_Power_Limit_Watts < 0) {
max_target_charge_power = 0; //cap calue so we dont do under the Fronius limits
} else {
max_target_charge_power = LB_Charge_Power_Limit_Watts;
}
if(SOC == 10000) //Scaled SOC% value is 100.00%
if (SOC == 10000) //Scaled SOC% value is 100.00%
{
max_target_charge_power = 0; //No need to charge further, set max power to 0
max_target_charge_power = 0; //No need to charge further, set max power to 0
}
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if(!CANstillAlive)
{
if (!CANstillAlive) {
bms_status = FAULT;
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
}
else
{
} else {
CANstillAlive--;
}
stat_batt_power;
temperature_min;
temperature_max;
#ifdef DEBUG_VIA_USB
Serial.print("BMS Status (3=OK): ");
Serial.println(bms_status);
Serial.print("Max discharge power: ");
Serial.println(max_target_discharge_power);
Serial.print("Max charge power: ");
Serial.println(max_target_charge_power);
Serial.print("SOH%: ");
Serial.println(LB_SOH);
Serial.print("SOH% to Fronius: ");
Serial.println(StateOfHealth);
Serial.print("LB_SOC: ");
Serial.println(LB_SOC);
Serial.print("SOC% to Fronius: ");
Serial.println(SOC);
Serial.print("Temperature Min: ");
Serial.println(temperature_min);
Serial.print("Temperature Max: ");
Serial.println(temperature_max);
#endif
stat_batt_power;
temperature_min;
temperature_max;
#ifdef DEBUG_VIA_USB
Serial.print("BMS Status (3=OK): ");
Serial.println(bms_status);
Serial.print("Max discharge power: ");
Serial.println(max_target_discharge_power);
Serial.print("Max charge power: ");
Serial.println(max_target_charge_power);
Serial.print("SOH%: ");
Serial.println(LB_SOH);
Serial.print("SOH% to Fronius: ");
Serial.println(StateOfHealth);
Serial.print("LB_SOC: ");
Serial.println(LB_SOC);
Serial.print("SOC% to Fronius: ");
Serial.println(SOC);
Serial.print("Temperature Min: ");
Serial.println(temperature_min);
Serial.print("Temperature Max: ");
Serial.println(temperature_max);
#endif
}
void receive_can_zoe_battery(CAN_frame_t rx_frame)
{
switch (rx_frame.MsgID)
{
case 0x155: //BMS1
CANstillAlive = 12; //Indicate that we are still getting CAN messages from the BMS
//LB_Max_Charge_Amps =
//LB_Current = (((rx_frame.data.u8[1] & 0xF8) << 5) | (rx_frame.data.u8[2]));
LB_SOC = ((rx_frame.data.u8[4] << 8) | (rx_frame.data.u8[5]));
break;
case 0x424: //BMS2
LB_Charge_Power_Limit = (rx_frame.data.u8[2]);
LB_Discharge_Power_Limit = (rx_frame.data.u8[3]);
LB_SOH = (rx_frame.data.u8[5]);
LB_MIN_TEMPERATURE = ((rx_frame.data.u8[4] & 0x7F) - 40);
LB_MAX_TEMPERATURE = ((rx_frame.data.u8[7] & 0x7F) - 40);
break;
case 0x425: //BMS3 (could also be 445?)
//LB_kWh_Remaining =
//LB_Cell_Max_Voltage =
//LB_Cell_Min_Voltage =
break;
default:
break;
void receive_can_zoe_battery(CAN_frame_t rx_frame) {
switch (rx_frame.MsgID) {
case 0x155: //BMS1
CANstillAlive = 12; //Indicate that we are still getting CAN messages from the BMS
//LB_Max_Charge_Amps =
//LB_Current = (((rx_frame.data.u8[1] & 0xF8) << 5) | (rx_frame.data.u8[2]));
LB_SOC = ((rx_frame.data.u8[4] << 8) | (rx_frame.data.u8[5]));
break;
case 0x424: //BMS2
LB_Charge_Power_Limit = (rx_frame.data.u8[2]);
LB_Discharge_Power_Limit = (rx_frame.data.u8[3]);
LB_SOH = (rx_frame.data.u8[5]);
LB_MIN_TEMPERATURE = ((rx_frame.data.u8[4] & 0x7F) - 40);
LB_MAX_TEMPERATURE = ((rx_frame.data.u8[7] & 0x7F) - 40);
break;
case 0x425: //BMS3 (could also be 445?)
//LB_kWh_Remaining =
//LB_Cell_Max_Voltage =
//LB_Cell_Min_Voltage =
break;
default:
break;
}
}
void send_can_zoe_battery()
{
void send_can_zoe_battery() {
unsigned long currentMillis = millis();
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100)
{
previousMillis100 = currentMillis;
BMSPollCounter++; //GKOE
if (currentMillis - previousMillis100 >= interval100) {
previousMillis100 = currentMillis;
BMSPollCounter++; //GKOE
if (BMSPollCounter < 46) //GKOE
{ //The Kangoo batteries (also Zoe?) dont like getting this message continously, so we pause after 4.6s, and resume after 40s
ESP32Can.CANWriteFrame(&ZOE_423); //Send 0x423 to keep BMS happy
}
if (BMSPollCounter > 400) //GKOE
ESP32Can.CANWriteFrame(&ZOE_423); //Send 0x423 to keep BMS happy
}
if (BMSPollCounter > 400) //GKOE
{
BMSPollCounter = 0;
}

View file

@ -1,11 +1,12 @@
#ifndef RENAULT_ZOE_BATTERY_H
#define RENAULT_ZOE_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4040 // 404.4V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 3100 // 310.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped for the Gen24
extern uint16_t SOC;
@ -35,4 +36,4 @@ void receive_can_zoe_battery(CAN_frame_t rx_frame);
void send_can_zoe_battery();
uint16_t convert2unsignedint16(uint16_t signed_value);
#endif
#endif

View file

@ -5,21 +5,35 @@
/* Do not change code below unless you are sure what you are doing */
/* Credits: Most of the code comes from Per Carlen's bms_comms_tesla_model3.py (https://gitlab.com/pelle8/batt2gen24/) */
static unsigned long previousMillis30 = 0; // will store last time a 30ms CAN Message was send
static const int interval30 = 30; // interval (ms) at which send CAN Messages
static uint8_t stillAliveCAN = 6; //counter for checking if CAN is still alive
static unsigned long previousMillis30 = 0; // will store last time a 30ms CAN Message was send
static const int interval30 = 30; // interval (ms) at which send CAN Messages
static uint8_t stillAliveCAN = 6; //counter for checking if CAN is still alive
CAN_frame_t TESLA_221_1 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x221,.data = {0x41, 0x11, 0x01, 0x00, 0x00, 0x00, 0x20, 0x96}}; //Contactor frame 221 - close contactors
CAN_frame_t TESLA_221_2 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x221,.data = {0x61, 0x15, 0x01, 0x00, 0x00, 0x00, 0x20, 0xBA}}; //Contactor Frame 221 - hv_up_for_drive
CAN_frame_t TESLA_221_1 = {
.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x221,
.data = {0x41, 0x11, 0x01, 0x00, 0x00, 0x00, 0x20, 0x96}}; //Contactor frame 221 - close contactors
CAN_frame_t TESLA_221_2 = {
.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x221,
.data = {0x61, 0x15, 0x01, 0x00, 0x00, 0x00, 0x20, 0xBA}}; //Contactor Frame 221 - hv_up_for_drive
static uint32_t temporaryvariable = 0;
static uint32_t total_discharge = 0;
static uint32_t total_charge = 0;
static uint16_t volts = 0; // V
static int16_t amps = 0; // A
static uint16_t raw_amps = 0; // A
static int16_t max_temp = 6; // C*
static int16_t min_temp = 5; // C*
static uint16_t volts = 0; // V
static int16_t amps = 0; // A
static uint16_t raw_amps = 0; // A
static int16_t max_temp = 6; // C*
static int16_t min_temp = 5; // C*
static uint16_t energy_buffer = 0;
static uint16_t energy_to_charge_complete = 0;
static uint16_t expected_energy_remaining = 0;
@ -27,7 +41,7 @@ static uint8_t full_charge_complete = 0;
static uint16_t ideal_energy_remaining = 0;
static uint16_t nominal_energy_remaining = 0;
static uint16_t nominal_full_pack_energy = 0;
static uint16_t battery_charge_time_remaining = 0; // Minutes
static uint16_t battery_charge_time_remaining = 0; // Minutes
static uint16_t regenerative_limit = 0;
static uint16_t discharge_limit = 0;
static uint16_t max_heat_park = 0;
@ -46,10 +60,10 @@ static uint16_t soc_calculated = 0;
static uint16_t soc_ave = 0;
static uint16_t cell_max_v = 3700;
static uint16_t cell_min_v = 3700;
static uint16_t cell_deviation_mV = 0; //contains the deviation between highest and lowest cell in mV
static uint16_t cell_deviation_mV = 0; //contains the deviation between highest and lowest cell in mV
static uint8_t max_vno = 0;
static uint8_t min_vno = 0;
static uint8_t contactor = 0; //State of contactor
static uint8_t contactor = 0; //State of contactor
static uint8_t hvil_status = 0;
static uint8_t packContNegativeState = 0;
static uint8_t packContPositiveState = 0;
@ -58,38 +72,41 @@ static uint8_t packCtrsClosingAllowed = 0;
static uint8_t pyroTestInProgress = 0;
static uint8_t send221still = 10;
static uint8_t LFP_Chemistry = 0;
//Fault codes
static uint8_t WatchdogReset = 0; //Warns if the processor has experienced a reset due to watchdog reset.
static uint8_t PowerLossReset = 0; //Warns if the processor has experienced a reset due to power loss.
static uint8_t SwAssertion = 0; //An internal software assertion has failed.
static uint8_t CrashEvent = 0; //Warns if the crash signal is detected by HVP
static uint8_t OverDchgCurrentFault = 0; //Warns if the pack discharge is above max discharge current limit
//Fault codes
static uint8_t WatchdogReset = 0; //Warns if the processor has experienced a reset due to watchdog reset.
static uint8_t PowerLossReset = 0; //Warns if the processor has experienced a reset due to power loss.
static uint8_t SwAssertion = 0; //An internal software assertion has failed.
static uint8_t CrashEvent = 0; //Warns if the crash signal is detected by HVP
static uint8_t OverDchgCurrentFault = 0; //Warns if the pack discharge is above max discharge current limit
static uint8_t OverChargeCurrentFault = 0; //Warns if the pack discharge current is above max charge current limit
static uint8_t OverCurrentFault = 0; //Warns if the pack current (discharge or charge) is above max current limit.
static uint8_t OverTemperatureFault = 0; //A pack module temperature is above maximum temperature limit
static uint8_t OverVoltageFault= 0; //A brick voltage is above maximum voltage limit
static uint8_t UnderVoltageFault = 0; //A brick voltage is below minimum voltage limit
static uint8_t PrimaryBmbMiaFault = 0; //Warns if the voltage and temperature readings from primary BMB chain are mia
static uint8_t SecondaryBmbMiaFault = 0; //Warns if the voltage and temperature readings from secondary BMB chain are mia
static uint8_t BmbMismatchFault = 0; //Warns if the primary and secondary BMB chain readings don't match with each other
static uint8_t BmsHviMiaFault = 0; //Warns if the BMS node is mia on HVS or HVI CAN
static uint8_t CpMiaFault = 0; //Warns if the CP node is mia on HVS CAN
static uint8_t PcsMiaFault = 0; //The PCS node is mia on HVS CAN
static uint8_t BmsFault = 0; //Warns if the BMS ECU has faulted
static uint8_t PcsFault = 0; //Warns if the PCS ECU has faulted
static uint8_t CpFault = 0; //Warns if the CP ECU has faulted
static uint8_t ShuntHwMiaFault = 0; //Warns if the shunt current reading is not available
static uint8_t PyroMiaFault = 0; //Warns if the pyro squib is not connected
static uint8_t hvsMiaFault = 0; //Warns if the pack contactor hw fault
static uint8_t hviMiaFault = 0; //Warns if the FC contactor hw fault
static uint8_t Supply12vFault = 0; //Warns if the low voltage (12V) battery is below minimum voltage threshold
static uint8_t VerSupplyFault = 0; //Warns if the Energy reserve voltage supply is below minimum voltage threshold
static uint8_t HvilFault = 0; //Warn if a High Voltage Inter Lock fault is detected
static uint8_t BmsHvsMiaFault = 0; //Warns if the BMS node is mia on HVS or HVI CAN
static uint8_t PackVoltMismatchFault = 0; //Warns if the pack voltage doesn't match approximately with sum of brick voltages
static uint8_t EnsMiaFault = 0; //Warns if the ENS line is not connected to HVC
static uint8_t PackPosCtrArcFault = 0; //Warns if the HVP detectes series arc at pack contactor
static uint8_t packNegCtrArcFault = 0; //Warns if the HVP detectes series arc at FC contactor
static uint8_t OverCurrentFault = 0; //Warns if the pack current (discharge or charge) is above max current limit.
static uint8_t OverTemperatureFault = 0; //A pack module temperature is above maximum temperature limit
static uint8_t OverVoltageFault = 0; //A brick voltage is above maximum voltage limit
static uint8_t UnderVoltageFault = 0; //A brick voltage is below minimum voltage limit
static uint8_t PrimaryBmbMiaFault = 0; //Warns if the voltage and temperature readings from primary BMB chain are mia
static uint8_t SecondaryBmbMiaFault =
0; //Warns if the voltage and temperature readings from secondary BMB chain are mia
static uint8_t BmbMismatchFault =
0; //Warns if the primary and secondary BMB chain readings don't match with each other
static uint8_t BmsHviMiaFault = 0; //Warns if the BMS node is mia on HVS or HVI CAN
static uint8_t CpMiaFault = 0; //Warns if the CP node is mia on HVS CAN
static uint8_t PcsMiaFault = 0; //The PCS node is mia on HVS CAN
static uint8_t BmsFault = 0; //Warns if the BMS ECU has faulted
static uint8_t PcsFault = 0; //Warns if the PCS ECU has faulted
static uint8_t CpFault = 0; //Warns if the CP ECU has faulted
static uint8_t ShuntHwMiaFault = 0; //Warns if the shunt current reading is not available
static uint8_t PyroMiaFault = 0; //Warns if the pyro squib is not connected
static uint8_t hvsMiaFault = 0; //Warns if the pack contactor hw fault
static uint8_t hviMiaFault = 0; //Warns if the FC contactor hw fault
static uint8_t Supply12vFault = 0; //Warns if the low voltage (12V) battery is below minimum voltage threshold
static uint8_t VerSupplyFault = 0; //Warns if the Energy reserve voltage supply is below minimum voltage threshold
static uint8_t HvilFault = 0; //Warn if a High Voltage Inter Lock fault is detected
static uint8_t BmsHvsMiaFault = 0; //Warns if the BMS node is mia on HVS or HVI CAN
static uint8_t PackVoltMismatchFault =
0; //Warns if the pack voltage doesn't match approximately with sum of brick voltages
static uint8_t EnsMiaFault = 0; //Warns if the ENS line is not connected to HVC
static uint8_t PackPosCtrArcFault = 0; //Warns if the HVP detectes series arc at pack contactor
static uint8_t packNegCtrArcFault = 0; //Warns if the HVP detectes series arc at FC contactor
static uint8_t ShuntHwAndBmsMiaFault = 0;
static uint8_t fcContHwFault = 0;
static uint8_t robinOverVoltageFault = 0;
@ -110,75 +127,87 @@ static uint8_t logUploadRequest = 0;
static uint8_t packCtrCloseFailed = 0;
static uint8_t fcCtrCloseFailed = 0;
static uint8_t shuntThermistorMia = 0;
static const char* contactorText[] = {"UNKNOWN(0)","OPEN","CLOSING","BLOCKED","OPENING","CLOSED","UNKNOWN(6)","WELDED","POS_CL","NEG_CL","UNKNOWN(10)","UNKNOWN(11)","UNKNOWN(12)"};
static const char* contactorState[] = {"SNA","OPEN","PRECHARGE","BLOCKED","PULLED_IN","OPENING","ECONOMIZED","WELDED","UNKNOWN(8)","UNKNOWN(9)","UNKNOWN(10)","UNKNOWN(11)"};
static const char* hvilStatusState[] = {"NOT OK","STATUS_OK","CURRENT_SOURCE_FAULT","INTERNAL_OPEN_FAULT","VEHICLE_OPEN_FAULT","PENTHOUSE_LID_OPEN_FAULT","UNKNOWN_LOCATION_OPEN_FAULT","VEHICLE_NODE_FAULT","NO_12V_SUPPLY","VEHICLE_OR_PENTHOUSE_LID_OPENFAULT","UNKNOWN(10)","UNKNOWN(11)","UNKNOWN(12)","UNKNOWN(13)","UNKNOWN(14)","UNKNOWN(15)"};
static const char* contactorText[] = {"UNKNOWN(0)", "OPEN", "CLOSING", "BLOCKED", "OPENING",
"CLOSED", "UNKNOWN(6)", "WELDED", "POS_CL", "NEG_CL",
"UNKNOWN(10)", "UNKNOWN(11)", "UNKNOWN(12)"};
static const char* contactorState[] = {"SNA", "OPEN", "PRECHARGE", "BLOCKED",
"PULLED_IN", "OPENING", "ECONOMIZED", "WELDED",
"UNKNOWN(8)", "UNKNOWN(9)", "UNKNOWN(10)", "UNKNOWN(11)"};
static const char* hvilStatusState[] = {"NOT OK",
"STATUS_OK",
"CURRENT_SOURCE_FAULT",
"INTERNAL_OPEN_FAULT",
"VEHICLE_OPEN_FAULT",
"PENTHOUSE_LID_OPEN_FAULT",
"UNKNOWN_LOCATION_OPEN_FAULT",
"VEHICLE_NODE_FAULT",
"NO_12V_SUPPLY",
"VEHICLE_OR_PENTHOUSE_LID_OPENFAULT",
"UNKNOWN(10)",
"UNKNOWN(11)",
"UNKNOWN(12)",
"UNKNOWN(13)",
"UNKNOWN(14)",
"UNKNOWN(15)"};
#define MAX_SOC 1000 //BMS never goes over this value. We use this info to rescale SOC% sent to inverter
#define MIN_SOC 0 //BMS never goes below this value. We use this info to rescale SOC% sent to inverter
#define MAX_CELL_VOLTAGE_NCA_NCM 4250 //Battery is put into emergency stop if one cell goes over this value
#define MIN_CELL_VOLTAGE_NCA_NCM 2950 //Battery is put into emergency stop if one cell goes below this value
#define MAX_CELL_DEVIATION_NCA_NCM 500 //LED turns yellow on the board if mv delta exceeds this value
#define MAX_CELL_VOLTAGE_NCA_NCM 4250 //Battery is put into emergency stop if one cell goes over this value
#define MIN_CELL_VOLTAGE_NCA_NCM 2950 //Battery is put into emergency stop if one cell goes below this value
#define MAX_CELL_DEVIATION_NCA_NCM 500 //LED turns yellow on the board if mv delta exceeds this value
#define MAX_CELL_VOLTAGE_LFP 3450 //Battery is put into emergency stop if one cell goes over this value
#define MIN_CELL_VOLTAGE_LFP 2800 //Battery is put into emergency stop if one cell goes over this value
#define MAX_CELL_DEVIATION_LFP 150 //LED turns yellow on the board if mv delta exceeds this value
#define MAX_CELL_VOLTAGE_LFP 3450 //Battery is put into emergency stop if one cell goes over this value
#define MIN_CELL_VOLTAGE_LFP 2800 //Battery is put into emergency stop if one cell goes over this value
#define MAX_CELL_DEVIATION_LFP 150 //LED turns yellow on the board if mv delta exceeds this value
void update_values_tesla_model_3_battery()
{ //This function maps all the values fetched via CAN to the correct parameters used for modbus
void update_values_tesla_model_3_battery() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
//After values are mapped, we perform some safety checks, and do some serial printouts
StateOfHealth = 9900; //Hardcoded to 99%SOH
StateOfHealth = 9900; //Hardcoded to 99%SOH
//Calculate the SOC% value to send to inverter
soc_calculated = soc_vi;
soc_calculated = MIN_SOC + (MAX_SOC - MIN_SOC) * (soc_calculated - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
if (soc_calculated < 0)
{ //We are in the real SOC% range of 0-20%, always set SOC sent to Inverter as 0%
soc_calculated = 0;
soc_calculated = MIN_SOC + (MAX_SOC - MIN_SOC) * (soc_calculated - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
if (soc_calculated < 0) { //We are in the real SOC% range of 0-20%, always set SOC sent to Inverter as 0%
soc_calculated = 0;
}
if (soc_calculated > 1000)
{ //We are in the real SOC% range of 80-100%, always set SOC sent to Inverter as 100%
soc_calculated = 1000;
if (soc_calculated > 1000) { //We are in the real SOC% range of 80-100%, always set SOC sent to Inverter as 100%
soc_calculated = 1000;
}
SOC = (soc_calculated * 10); //increase SOC range from 0-100.0 -> 100.00
SOC = (soc_calculated * 10); //increase SOC range from 0-100.0 -> 100.00
battery_voltage = (volts*10); //One more decimal needed (370 -> 3700)
battery_voltage = (volts * 10); //One more decimal needed (370 -> 3700)
battery_current = amps; //TODO, this needs verifying if scaling is right
battery_current = amps; //TODO, this needs verifying if scaling is right
capacity_Wh = (nominal_full_pack_energy * 100); //Scale up 75.2kWh -> 75200Wh
if(capacity_Wh > 60000)
{
capacity_Wh = (nominal_full_pack_energy * 100); //Scale up 75.2kWh -> 75200Wh
if (capacity_Wh > 60000) {
capacity_Wh = 60000;
}
remaining_capacity_Wh = (expected_energy_remaining * 100); //Scale up 60.3kWh -> 60300Wh
remaining_capacity_Wh = (expected_energy_remaining * 100); //Scale up 60.3kWh -> 60300Wh
//Calculate the allowed discharge power, cap it if it gets too large
temporaryvariable = (max_discharge_current * volts);
if(temporaryvariable > 60000){
if (temporaryvariable > 60000) {
max_target_discharge_power = 60000;
}
else{
} else {
max_target_discharge_power = temporaryvariable;
}
//The allowed charge power behaves strangely. We instead estimate this value
if(SOC == 10000){
max_target_charge_power = 0; //When battery is 100% full, set allowed charge W to 0
}
else{
max_target_charge_power = 15000; //Otherwise we can push 15kW into the pack!
if (SOC == 10000) {
max_target_charge_power = 0; //When battery is 100% full, set allowed charge W to 0
} else {
max_target_charge_power = 15000; //Otherwise we can push 15kW into the pack!
}
stat_batt_power = (volts * amps); //TODO, check if scaling is OK
stat_batt_power = (volts * amps); //TODO, check if scaling is OK
min_temp = (min_temp * 10);
temperature_min = convert2unsignedInt16(min_temp);
temperature_min = convert2unsignedInt16(min_temp);
max_temp = (max_temp * 10);
temperature_max = convert2unsignedInt16(max_temp);
temperature_max = convert2unsignedInt16(max_temp);
cell_max_voltage = cell_max_v;
@ -186,357 +215,355 @@ void update_values_tesla_model_3_battery()
/* Value mapping is completed. Start to check all safeties */
bms_status = ACTIVE; //Startout in active mode before checking if we have any faults
bms_status = ACTIVE; //Startout in active mode before checking if we have any faults
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if(!stillAliveCAN)
{
bms_status = FAULT;
Serial.println("ERROR: No CAN communication detected for 60s. Shutting down battery control.");
}
else
{
stillAliveCAN--;
}
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
if (!stillAliveCAN) {
bms_status = FAULT;
Serial.println("ERROR: No CAN communication detected for 60s. Shutting down battery control.");
} else {
stillAliveCAN--;
}
if (hvil_status == 3){ //INTERNAL_OPEN_FAULT - Someone disconnected a high voltage cable while battery was in use
if (hvil_status == 3) { //INTERNAL_OPEN_FAULT - Someone disconnected a high voltage cable while battery was in use
bms_status = FAULT;
Serial.println("ERROR: High voltage cable removed while battery running. Opening contactors!");
}
}
cell_deviation_mV = (cell_max_v - cell_min_v);
//Determine which chemistry battery pack is using (crude method, TODO, replace with real CAN data later)
if(soc_vi > 900){ //When SOC% is over 90.0%, we can use max cell voltage to estimate what chemistry is used
if(cell_max_v < 3450){
if (soc_vi > 900) { //When SOC% is over 90.0%, we can use max cell voltage to estimate what chemistry is used
if (cell_max_v < 3450) {
LFP_Chemistry = 1;
}
if(cell_max_v > 3700){
if (cell_max_v > 3700) {
LFP_Chemistry = 0;
}
}
if(LFP_Chemistry){ //LFP limits used for voltage safeties
if(cell_max_v >= MAX_CELL_VOLTAGE_LFP){
if (LFP_Chemistry) { //LFP limits used for voltage safeties
if (cell_max_v >= MAX_CELL_VOLTAGE_LFP) {
bms_status = FAULT;
Serial.println("ERROR: CELL OVERVOLTAGE!!! Stopping battery charging and discharging. Inspect battery!");
}
if(cell_min_v <= MIN_CELL_VOLTAGE_LFP){
if (cell_min_v <= MIN_CELL_VOLTAGE_LFP) {
bms_status = FAULT;
Serial.println("ERROR: CELL UNDERVOLTAGE!!! Stopping battery charging and discharging. Inspect battery!");
}
if(cell_deviation_mV > MAX_CELL_DEVIATION_LFP){
if (cell_deviation_mV > MAX_CELL_DEVIATION_LFP) {
LEDcolor = YELLOW;
Serial.println("ERROR: HIGH CELL DEVIATION!!! Inspect battery!");
}
} else { //NCA/NCM limits used
if (cell_max_v >= MAX_CELL_VOLTAGE_NCA_NCM) {
bms_status = FAULT;
Serial.println("ERROR: CELL OVERVOLTAGE!!! Stopping battery charging and discharging. Inspect battery!");
}
if (cell_min_v <= MIN_CELL_VOLTAGE_NCA_NCM) {
bms_status = FAULT;
Serial.println("ERROR: CELL UNDERVOLTAGE!!! Stopping battery charging and discharging. Inspect battery!");
}
if (cell_deviation_mV > MAX_CELL_DEVIATION_NCA_NCM) {
LEDcolor = YELLOW;
Serial.println("ERROR: HIGH CELL DEVIATION!!! Inspect battery!");
}
}
else{ //NCA/NCM limits used
if(cell_max_v >= MAX_CELL_VOLTAGE_NCA_NCM){
bms_status = FAULT;
Serial.println("ERROR: CELL OVERVOLTAGE!!! Stopping battery charging and discharging. Inspect battery!");
}
if(cell_min_v <= MIN_CELL_VOLTAGE_NCA_NCM){
bms_status = FAULT;
Serial.println("ERROR: CELL UNDERVOLTAGE!!! Stopping battery charging and discharging. Inspect battery!");
}
if(cell_deviation_mV > MAX_CELL_DEVIATION_NCA_NCM){
LEDcolor = YELLOW;
Serial.println("ERROR: HIGH CELL DEVIATION!!! Inspect battery!");
}
}
/* Safeties verified. Perform USB serial printout if configured to do so */
#ifdef DEBUG_VIA_USB
#ifdef DEBUG_VIA_USB
printFaultCodesIfActive();
printFaultCodesIfActive();
Serial.print("STATUS: Contactor: ");
Serial.print(contactorText[contactor]); //Display what state the contactor is in
Serial.print(", HVIL: ");
Serial.print(hvilStatusState[hvil_status]);
Serial.print(", NegativeState: ");
Serial.print(contactorState[packContNegativeState]);
Serial.print(", PositiveState: ");
Serial.print(contactorState[packContPositiveState]);
Serial.print(", setState: ");
Serial.print(contactorState[packContactorSetState]);
Serial.print(", close allowed: ");
Serial.print(packCtrsClosingAllowed);
Serial.print(", Pyrotest: ");
Serial.println(pyroTestInProgress);
Serial.print("STATUS: Contactor: ");
Serial.print(contactorText[contactor]); //Display what state the contactor is in
Serial.print(", HVIL: ");
Serial.print(hvilStatusState[hvil_status]);
Serial.print(", NegativeState: ");
Serial.print(contactorState[packContNegativeState]);
Serial.print(", PositiveState: ");
Serial.print(contactorState[packContPositiveState]);
Serial.print(", setState: ");
Serial.print(contactorState[packContactorSetState]);
Serial.print(", close allowed: ");
Serial.print(packCtrsClosingAllowed);
Serial.print(", Pyrotest: ");
Serial.println(pyroTestInProgress);
Serial.print("Battery values: ");
Serial.print("Real SOC: ");
Serial.print(soc_vi);
print_int_with_units(", Battery voltage: ", volts, "V");
print_int_with_units(", Battery current: ", amps, "A");
Serial.println("");
print_int_with_units("Discharge limit battery: ", discharge_limit, "kW");
Serial.print(", ");
print_int_with_units("Charge limit battery: ", regenerative_limit, "kW");
Serial.print(", Fully charged?: ");
if(full_charge_complete)
Serial.print("YES, ");
else
Serial.print("NO, ");
print_int_with_units("Min voltage allowed: ", min_voltage, "V");
Serial.print(", ");
print_int_with_units("Max voltage allowed: ", max_voltage, "V");
Serial.println("");
print_int_with_units("Max charge current: ", max_charge_current, "A");
Serial.print(", ");
print_int_with_units("Max discharge current: ", max_discharge_current, "A");
Serial.println("");
Serial.print("Cellstats, Max: ");
Serial.print(cell_max_v);
Serial.print("mV (cell ");
Serial.print(max_vno);
Serial.print("), Min: ");
Serial.print(cell_min_v);
Serial.print("mV (cell ");
Serial.print(min_vno);
Serial.print("), Imbalance: ");
Serial.print(cell_deviation_mV);
Serial.println("mV.");
Serial.print("Battery values: ");
Serial.print("Real SOC: ");
Serial.print(soc_vi);
print_int_with_units(", Battery voltage: ", volts, "V");
print_int_with_units(", Battery current: ", amps, "A");
Serial.println("");
print_int_with_units("Discharge limit battery: ", discharge_limit, "kW");
Serial.print(", ");
print_int_with_units("Charge limit battery: ", regenerative_limit, "kW");
Serial.print(", Fully charged?: ");
if (full_charge_complete)
Serial.print("YES, ");
else
Serial.print("NO, ");
print_int_with_units("Min voltage allowed: ", min_voltage, "V");
Serial.print(", ");
print_int_with_units("Max voltage allowed: ", max_voltage, "V");
Serial.println("");
print_int_with_units("Max charge current: ", max_charge_current, "A");
Serial.print(", ");
print_int_with_units("Max discharge current: ", max_discharge_current, "A");
Serial.println("");
Serial.print("Cellstats, Max: ");
Serial.print(cell_max_v);
Serial.print("mV (cell ");
Serial.print(max_vno);
Serial.print("), Min: ");
Serial.print(cell_min_v);
Serial.print("mV (cell ");
Serial.print(min_vno);
Serial.print("), Imbalance: ");
Serial.print(cell_deviation_mV);
Serial.println("mV.");
print_int_with_units("High Voltage Output Pins: ", high_voltage, "V");
Serial.print(", ");
print_int_with_units("Low Voltage: ", low_voltage, "V");
Serial.println("");
print_int_with_units("Current Output: ", output_current, "A");
Serial.println("");
print_int_with_units("High Voltage Output Pins: ", high_voltage, "V");
Serial.print(", ");
print_int_with_units("Low Voltage: ", low_voltage, "V");
Serial.println("");
print_int_with_units("Current Output: ", output_current, "A");
Serial.println("");
Serial.println("Values passed to the inverter: ");
print_SOC(" SOC: ", SOC);
print_int_with_units(" Max discharge power: ", max_target_discharge_power, "W");
Serial.print(", ");
print_int_with_units(" Max charge power: ", max_target_charge_power, "W");
Serial.println("");
print_int_with_units(" Max temperature: ", temperature_max, "C");
Serial.print(", ");
print_int_with_units(" Min temperature: ", temperature_min, "C");
Serial.println("");
#endif
Serial.println("Values passed to the inverter: ");
print_SOC(" SOC: ", SOC);
print_int_with_units(" Max discharge power: ", max_target_discharge_power, "W");
Serial.print(", ");
print_int_with_units(" Max charge power: ", max_target_charge_power, "W");
Serial.println("");
print_int_with_units(" Max temperature: ", temperature_max, "C");
Serial.print(", ");
print_int_with_units(" Min temperature: ", temperature_min, "C");
Serial.println("");
#endif
}
void receive_can_tesla_model_3_battery(CAN_frame_t rx_frame)
{
void receive_can_tesla_model_3_battery(CAN_frame_t rx_frame) {
static int mux = 0;
static int temp = 0;
switch (rx_frame.MsgID)
{
switch (rx_frame.MsgID) {
case 0x352:
//SOC
nominal_full_pack_energy = (((rx_frame.data.u8[1] & 0x0F) << 8) | (rx_frame.data.u8[0])); //Example 752 (75.2kWh)
nominal_energy_remaining = (((rx_frame.data.u8[2] & 0x3F) << 5) | ((rx_frame.data.u8[1] & 0xF8) >> 3)) * 0.1; //Example 1247 * 0.1 = 124.7kWh
expected_energy_remaining = (((rx_frame.data.u8[4] & 0x01) << 10) | (rx_frame.data.u8[3] << 2) | ((rx_frame.data.u8[2] & 0xC0) >> 6)); //Example 622 (62.2kWh)
ideal_energy_remaining = (((rx_frame.data.u8[5] & 0x0F) << 7) | ((rx_frame.data.u8[4] & 0xFE) >> 1)) * 0.1; //Example 311 * 0.1 = 31.1kWh
energy_to_charge_complete = (((rx_frame.data.u8[6] & 0x7F) << 4) | ((rx_frame.data.u8[5] & 0xF0) >> 4)) * 0.1; //Example 147 * 0.1 = 14.7kWh
energy_buffer = (((rx_frame.data.u8[7] & 0x7F) << 1) | ((rx_frame.data.u8[6] & 0x80) >> 7)) * 0.1; //Example 1 * 0.1 = 0
full_charge_complete = ((rx_frame.data.u8[7] & 0x80) >> 7);
nominal_full_pack_energy = (((rx_frame.data.u8[1] & 0x0F) << 8) | (rx_frame.data.u8[0])); //Example 752 (75.2kWh)
nominal_energy_remaining = (((rx_frame.data.u8[2] & 0x3F) << 5) | ((rx_frame.data.u8[1] & 0xF8) >> 3)) *
0.1; //Example 1247 * 0.1 = 124.7kWh
expected_energy_remaining = (((rx_frame.data.u8[4] & 0x01) << 10) | (rx_frame.data.u8[3] << 2) |
((rx_frame.data.u8[2] & 0xC0) >> 6)); //Example 622 (62.2kWh)
ideal_energy_remaining = (((rx_frame.data.u8[5] & 0x0F) << 7) | ((rx_frame.data.u8[4] & 0xFE) >> 1)) *
0.1; //Example 311 * 0.1 = 31.1kWh
energy_to_charge_complete = (((rx_frame.data.u8[6] & 0x7F) << 4) | ((rx_frame.data.u8[5] & 0xF0) >> 4)) *
0.1; //Example 147 * 0.1 = 14.7kWh
energy_buffer =
(((rx_frame.data.u8[7] & 0x7F) << 1) | ((rx_frame.data.u8[6] & 0x80) >> 7)) * 0.1; //Example 1 * 0.1 = 0
full_charge_complete = ((rx_frame.data.u8[7] & 0x80) >> 7);
break;
case 0x20A:
//Contactor state
packContNegativeState = (rx_frame.data.u8[0] & 0x07);
packContPositiveState = (rx_frame.data.u8[0] & 0x38) >> 3;
contactor = (rx_frame.data.u8[1] & 0x0F);
packContactorSetState = (rx_frame.data.u8[1] & 0x0F);
packCtrsClosingAllowed = (rx_frame.data.u8[4] & 0x08) >> 3;
pyroTestInProgress = (rx_frame.data.u8[4] & 0x20) >> 5;
hvil_status = (rx_frame.data.u8[5] & 0x0F);
packContNegativeState = (rx_frame.data.u8[0] & 0x07);
packContPositiveState = (rx_frame.data.u8[0] & 0x38) >> 3;
contactor = (rx_frame.data.u8[1] & 0x0F);
packContactorSetState = (rx_frame.data.u8[1] & 0x0F);
packCtrsClosingAllowed = (rx_frame.data.u8[4] & 0x08) >> 3;
pyroTestInProgress = (rx_frame.data.u8[4] & 0x20) >> 5;
hvil_status = (rx_frame.data.u8[5] & 0x0F);
break;
case 0x252:
//Limits
regenerative_limit = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01; //Example 4715 * 0.01 = 47.15kW
discharge_limit = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]) * 0.013; //Example 2009 * 0.013 = 26.117???
max_heat_park = (((rx_frame.data.u8[5] & 0x03) << 8) | rx_frame.data.u8[4]) * 0.01; //Example 500 * 0.01 = 5kW
hvac_max_power = (((rx_frame.data.u8[7] << 6) | ((rx_frame.data.u8[6] & 0xFC) >> 2))) * 0.02; //Example 1000 * 0.02 = 20kW?
regenerative_limit = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01; //Example 4715 * 0.01 = 47.15kW
discharge_limit = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]) * 0.013; //Example 2009 * 0.013 = 26.117???
max_heat_park = (((rx_frame.data.u8[5] & 0x03) << 8) | rx_frame.data.u8[4]) * 0.01; //Example 500 * 0.01 = 5kW
hvac_max_power =
(((rx_frame.data.u8[7] << 6) | ((rx_frame.data.u8[6] & 0xFC) >> 2))) * 0.02; //Example 1000 * 0.02 = 20kW?
break;
case 0x132:
//battery amps/volts
volts = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01; //Example 37030mv * 0.01 = 370V
amps = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]); //Example 65492 (-4.3A) OR 225 (22.5A)
if (amps > 32768)
{
amps = - (65535 - amps);
//battery amps/volts
volts = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01; //Example 37030mv * 0.01 = 370V
amps = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]); //Example 65492 (-4.3A) OR 225 (22.5A)
if (amps > 32768) {
amps = -(65535 - amps);
}
amps = amps * 0.1;
raw_amps = ((rx_frame.data.u8[5] << 8) | rx_frame.data.u8[4]) * -0.05; //Example 10425 * -0.05 = ?
battery_charge_time_remaining = (((rx_frame.data.u8[7] & 0x0F) << 8) | rx_frame.data.u8[6]) * 0.1; //Example 228 * 0.1 = 22.8min
if(battery_charge_time_remaining == 4095)
{
raw_amps = ((rx_frame.data.u8[5] << 8) | rx_frame.data.u8[4]) * -0.05; //Example 10425 * -0.05 = ?
battery_charge_time_remaining =
(((rx_frame.data.u8[7] & 0x0F) << 8) | rx_frame.data.u8[6]) * 0.1; //Example 228 * 0.1 = 22.8min
if (battery_charge_time_remaining == 4095) {
battery_charge_time_remaining = 0;
}
break;
case 0x3D2:
// total charge/discharge kwh
total_discharge = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) | (rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.001;
total_charge = ((rx_frame.data.u8[7] << 24) | (rx_frame.data.u8[6] << 16) | (rx_frame.data.u8[5] << 8) | rx_frame.data.u8[4]) * 0.001;
total_discharge = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) | (rx_frame.data.u8[1] << 8) |
rx_frame.data.u8[0]) *
0.001;
total_charge = ((rx_frame.data.u8[7] << 24) | (rx_frame.data.u8[6] << 16) | (rx_frame.data.u8[5] << 8) |
rx_frame.data.u8[4]) *
0.001;
break;
case 0x332:
//min/max hist values
mux = (rx_frame.data.u8[0] & 0x03);
if(mux == 1) //Cell voltages
if (mux == 1) //Cell voltages
{
temp = ((rx_frame.data.u8[1] << 6) | (rx_frame.data.u8[0] >> 2));
temp = (temp & 0xFFF);
cell_max_v = temp*2;
cell_max_v = temp * 2;
temp = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]);
temp = (temp & 0xFFF);
cell_min_v = temp*2;
max_vno = 1 + (rx_frame.data.u8[4] & 0x7F); //This cell has highest voltage
min_vno = 1 + (rx_frame.data.u8[5] & 0x7F); //This cell has lowest voltage
cell_min_v = temp * 2;
max_vno = 1 + (rx_frame.data.u8[4] & 0x7F); //This cell has highest voltage
min_vno = 1 + (rx_frame.data.u8[5] & 0x7F); //This cell has lowest voltage
}
if(mux == 0)//Temperature sensors
if (mux == 0) //Temperature sensors
{
temp = rx_frame.data.u8[2];
max_temp = (temp * 0.5) - 40; //in celcius, Example 24
max_temp = (temp * 0.5) - 40; //in celcius, Example 24
temp = rx_frame.data.u8[3];
min_temp = (temp * 0.5) - 40; //in celcius , Example 24
min_temp = (temp * 0.5) - 40; //in celcius , Example 24
}
break;
case 0x2d2:
//Min / max limits
min_voltage = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01 * 2; //Example 24148mv * 0.01 = 241.48 V
max_voltage = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]) * 0.01 * 2; //Example 40282mv * 0.01 = 402.82 V
max_charge_current = (((rx_frame.data.u8[5] & 0x3F) << 8) | rx_frame.data.u8[4]) * 0.1; //Example 1301? * 0.1 = 130.1?
max_discharge_current = (((rx_frame.data.u8[7] & 0x3F) << 8) | rx_frame.data.u8[6]) * 0.128; //Example 430? * 0.128 = 55.4?
min_voltage = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01 * 2; //Example 24148mv * 0.01 = 241.48 V
max_voltage = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]) * 0.01 * 2; //Example 40282mv * 0.01 = 402.82 V
max_charge_current =
(((rx_frame.data.u8[5] & 0x3F) << 8) | rx_frame.data.u8[4]) * 0.1; //Example 1301? * 0.1 = 130.1?
max_discharge_current =
(((rx_frame.data.u8[7] & 0x3F) << 8) | rx_frame.data.u8[6]) * 0.128; //Example 430? * 0.128 = 55.4?
break;
case 0x2b4:
low_voltage = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]) * 0.0390625;
high_voltage = (((rx_frame.data.u8[2] << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2))) * 0.146484;
output_current = (((rx_frame.data.u8[4] & 0x0F) << 8) | rx_frame.data.u8[3]) / 100;
low_voltage = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]) * 0.0390625;
high_voltage = (((rx_frame.data.u8[2] << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2))) * 0.146484;
output_current = (((rx_frame.data.u8[4] & 0x0F) << 8) | rx_frame.data.u8[3]) / 100;
break;
case 0x292:
stillAliveCAN = 12; //We are getting CAN messages from the BMS, set the CAN detect counter
stillAliveCAN = 12; //We are getting CAN messages from the BMS, set the CAN detect counter
soc_min = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]);
soc_vi = (((rx_frame.data.u8[2] & 0x0F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2));
soc_vi = (((rx_frame.data.u8[2] & 0x0F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2));
soc_max = (((rx_frame.data.u8[3] & 0x3F) << 4) | ((rx_frame.data.u8[2] & 0xF0) >> 4));
soc_ave = ((rx_frame.data.u8[4] << 2) | ((rx_frame.data.u8[3] & 0xC0) >> 6));
break;
case 0x3aa: //HVP_alertMatrix1
WatchdogReset = (rx_frame.data.u8[0] & 0x01);
PowerLossReset = ((rx_frame.data.u8[0] & 0x02) >> 1);
SwAssertion = ((rx_frame.data.u8[0] & 0x04) >> 2);
CrashEvent = ((rx_frame.data.u8[0] & 0x08) >> 3);
OverDchgCurrentFault = ((rx_frame.data.u8[0] & 0x10) >> 4);
OverChargeCurrentFault =((rx_frame.data.u8[0] & 0x20) >> 5);
OverCurrentFault = ((rx_frame.data.u8[0] & 0x40) >> 6);
OverTemperatureFault = ((rx_frame.data.u8[1] & 0x80) >> 7);
OverVoltageFault = (rx_frame.data.u8[1] & 0x01);
UnderVoltageFault = ((rx_frame.data.u8[1] & 0x02) >> 1);
PrimaryBmbMiaFault = ((rx_frame.data.u8[1] & 0x04) >> 2);
SecondaryBmbMiaFault = ((rx_frame.data.u8[1] & 0x08) >> 3);
BmbMismatchFault = ((rx_frame.data.u8[1] & 0x10) >> 4);
BmsHviMiaFault = ((rx_frame.data.u8[1] & 0x20) >> 5);
CpMiaFault = ((rx_frame.data.u8[1] & 0x40) >> 6);
PcsMiaFault = ((rx_frame.data.u8[1] & 0x80) >> 7);
BmsFault = (rx_frame.data.u8[2] & 0x01);
PcsFault = ((rx_frame.data.u8[2] & 0x02) >> 1);
CpFault = ((rx_frame.data.u8[2] & 0x04) >> 2);
ShuntHwMiaFault = ((rx_frame.data.u8[2] & 0x08) >> 3);
PyroMiaFault = ((rx_frame.data.u8[2] & 0x10) >> 4);
hvsMiaFault = ((rx_frame.data.u8[2] & 0x20) >> 5);
hviMiaFault = ((rx_frame.data.u8[2] & 0x40) >> 6);
Supply12vFault = ((rx_frame.data.u8[2] & 0x80) >> 7);
VerSupplyFault = (rx_frame.data.u8[3] & 0x01);
HvilFault = ((rx_frame.data.u8[3] & 0x02) >> 1);
BmsHvsMiaFault = ((rx_frame.data.u8[3] & 0x04) >> 2);
break;
case 0x3aa: //HVP_alertMatrix1
WatchdogReset = (rx_frame.data.u8[0] & 0x01);
PowerLossReset = ((rx_frame.data.u8[0] & 0x02) >> 1);
SwAssertion = ((rx_frame.data.u8[0] & 0x04) >> 2);
CrashEvent = ((rx_frame.data.u8[0] & 0x08) >> 3);
OverDchgCurrentFault = ((rx_frame.data.u8[0] & 0x10) >> 4);
OverChargeCurrentFault = ((rx_frame.data.u8[0] & 0x20) >> 5);
OverCurrentFault = ((rx_frame.data.u8[0] & 0x40) >> 6);
OverTemperatureFault = ((rx_frame.data.u8[1] & 0x80) >> 7);
OverVoltageFault = (rx_frame.data.u8[1] & 0x01);
UnderVoltageFault = ((rx_frame.data.u8[1] & 0x02) >> 1);
PrimaryBmbMiaFault = ((rx_frame.data.u8[1] & 0x04) >> 2);
SecondaryBmbMiaFault = ((rx_frame.data.u8[1] & 0x08) >> 3);
BmbMismatchFault = ((rx_frame.data.u8[1] & 0x10) >> 4);
BmsHviMiaFault = ((rx_frame.data.u8[1] & 0x20) >> 5);
CpMiaFault = ((rx_frame.data.u8[1] & 0x40) >> 6);
PcsMiaFault = ((rx_frame.data.u8[1] & 0x80) >> 7);
BmsFault = (rx_frame.data.u8[2] & 0x01);
PcsFault = ((rx_frame.data.u8[2] & 0x02) >> 1);
CpFault = ((rx_frame.data.u8[2] & 0x04) >> 2);
ShuntHwMiaFault = ((rx_frame.data.u8[2] & 0x08) >> 3);
PyroMiaFault = ((rx_frame.data.u8[2] & 0x10) >> 4);
hvsMiaFault = ((rx_frame.data.u8[2] & 0x20) >> 5);
hviMiaFault = ((rx_frame.data.u8[2] & 0x40) >> 6);
Supply12vFault = ((rx_frame.data.u8[2] & 0x80) >> 7);
VerSupplyFault = (rx_frame.data.u8[3] & 0x01);
HvilFault = ((rx_frame.data.u8[3] & 0x02) >> 1);
BmsHvsMiaFault = ((rx_frame.data.u8[3] & 0x04) >> 2);
PackVoltMismatchFault = ((rx_frame.data.u8[3] & 0x08) >> 3);
EnsMiaFault = ((rx_frame.data.u8[3] & 0x10) >> 4);
PackPosCtrArcFault = ((rx_frame.data.u8[3] & 0x20) >> 5);
packNegCtrArcFault = ((rx_frame.data.u8[3] & 0x40) >> 6);
EnsMiaFault = ((rx_frame.data.u8[3] & 0x10) >> 4);
PackPosCtrArcFault = ((rx_frame.data.u8[3] & 0x20) >> 5);
packNegCtrArcFault = ((rx_frame.data.u8[3] & 0x40) >> 6);
ShuntHwAndBmsMiaFault = ((rx_frame.data.u8[3] & 0x80) >> 7);
fcContHwFault = (rx_frame.data.u8[4] & 0x01);
fcContHwFault = (rx_frame.data.u8[4] & 0x01);
robinOverVoltageFault = ((rx_frame.data.u8[4] & 0x02) >> 1);
packContHwFault = ((rx_frame.data.u8[4] & 0x04) >> 2);
pyroFuseBlown = ((rx_frame.data.u8[4] & 0x08) >> 3);
pyroFuseFailedToBlow = ((rx_frame.data.u8[4] & 0x10) >> 4);
CpilFault = ((rx_frame.data.u8[4] & 0x20) >> 5);
packContHwFault = ((rx_frame.data.u8[4] & 0x04) >> 2);
pyroFuseBlown = ((rx_frame.data.u8[4] & 0x08) >> 3);
pyroFuseFailedToBlow = ((rx_frame.data.u8[4] & 0x10) >> 4);
CpilFault = ((rx_frame.data.u8[4] & 0x20) >> 5);
PackContactorFellOpen = ((rx_frame.data.u8[4] & 0x40) >> 6);
FcContactorFellOpen = ((rx_frame.data.u8[4] & 0x80) >> 7);
packCtrCloseBlocked = (rx_frame.data.u8[5] & 0x01);
fcCtrCloseBlocked = ((rx_frame.data.u8[5] & 0x02) >> 1);
packContactorForceOpen =((rx_frame.data.u8[5] & 0x04) >> 2);
fcContactorForceOpen = ((rx_frame.data.u8[5] & 0x08) >> 3);
dcLinkOverVoltage = ((rx_frame.data.u8[5] & 0x10) >> 4);
shuntOverTemperature = ((rx_frame.data.u8[5] & 0x20) >> 5);
passivePyroDeploy = ((rx_frame.data.u8[5] & 0x40) >> 6);
logUploadRequest = ((rx_frame.data.u8[5] & 0x80) >> 7);
packCtrCloseFailed = (rx_frame.data.u8[6] & 0x01);
fcCtrCloseFailed = ((rx_frame.data.u8[6] & 0x02) >> 1);
shuntThermistorMia = ((rx_frame.data.u8[6] & 0x04) >> 2);
break;
FcContactorFellOpen = ((rx_frame.data.u8[4] & 0x80) >> 7);
packCtrCloseBlocked = (rx_frame.data.u8[5] & 0x01);
fcCtrCloseBlocked = ((rx_frame.data.u8[5] & 0x02) >> 1);
packContactorForceOpen = ((rx_frame.data.u8[5] & 0x04) >> 2);
fcContactorForceOpen = ((rx_frame.data.u8[5] & 0x08) >> 3);
dcLinkOverVoltage = ((rx_frame.data.u8[5] & 0x10) >> 4);
shuntOverTemperature = ((rx_frame.data.u8[5] & 0x20) >> 5);
passivePyroDeploy = ((rx_frame.data.u8[5] & 0x40) >> 6);
logUploadRequest = ((rx_frame.data.u8[5] & 0x80) >> 7);
packCtrCloseFailed = (rx_frame.data.u8[6] & 0x01);
fcCtrCloseFailed = ((rx_frame.data.u8[6] & 0x02) >> 1);
shuntThermistorMia = ((rx_frame.data.u8[6] & 0x04) >> 2);
break;
default:
break;
}
}
void send_can_tesla_model_3_battery()
{
/*From bielec: My fist 221 message, to close the contactors is 0x41, 0x11, 0x01, 0x00, 0x00, 0x00, 0x20, 0x96 and then,
void send_can_tesla_model_3_battery() {
/*From bielec: My fist 221 message, to close the contactors is 0x41, 0x11, 0x01, 0x00, 0x00, 0x00, 0x20, 0x96 and then,
to cause "hv_up_for_drive" I send an additional 221 message 0x61, 0x15, 0x01, 0x00, 0x00, 0x00, 0x20, 0xBA so
two 221 messages are being continuously transmitted. When I want to shut down, I stop the second message and only send
the first, for a few cycles, then stop all messages which causes the contactor to open. */
unsigned long currentMillis = millis();
//Send 30ms message
if (currentMillis - previousMillis30 >= interval30)
{
previousMillis30 = currentMillis;
if (currentMillis - previousMillis30 >= interval30) {
previousMillis30 = currentMillis;
if(bms_status == ACTIVE){
if (bms_status == ACTIVE) {
send221still = 10;
ESP32Can.CANWriteFrame(&TESLA_221_1);
ESP32Can.CANWriteFrame(&TESLA_221_2);
}
else{ //bms_status == FAULT
if(send221still > 0){
} else { //bms_status == FAULT
if (send221still > 0) {
ESP32Can.CANWriteFrame(&TESLA_221_1);
send221still--;
}
}
}
}
}
uint16_t convert2unsignedInt16(int16_t signed_value)
{
if(signed_value < 0){
return(65535 + signed_value);
}
else{
return (uint16_t)signed_value;
}
uint16_t convert2unsignedInt16(int16_t signed_value) {
if (signed_value < 0) {
return (65535 + signed_value);
} else {
return (uint16_t)signed_value;
}
}
void print_int_with_units(char *header, int value, char *units) {
Serial.print(header);
Serial.print(value);
Serial.print(units);
void print_int_with_units(char* header, int value, char* units) {
Serial.print(header);
Serial.print(value);
Serial.print(units);
}
void print_SOC(char *header, int SOC) {
void print_SOC(char* header, int SOC) {
Serial.print(header);
Serial.print(SOC / 100);
Serial.print(".");
int hundredth = SOC % 100;
if(hundredth < 10)
if (hundredth < 10)
Serial.print(0);
Serial.print(hundredth);
Serial.println("%");
}
void printFaultCodesIfActive(){
if (packCtrsClosingAllowed == 0)
{
Serial.println("ERROR: Check high voltage connectors and interlock circuit! Closing contactor not allowed! Values: ");
void printFaultCodesIfActive() {
if (packCtrsClosingAllowed == 0) {
Serial.println(
"ERROR: Check high voltage connectors and interlock circuit! Closing contactor not allowed! Values: ");
}
if (pyroTestInProgress == 1)
{
if (pyroTestInProgress == 1) {
Serial.println("ERROR: Please wait for Pyro Connection check to finish, HV cables successfully seated!");
}
@ -545,7 +572,8 @@ void printFaultCodesIfActive(){
printDebugIfActive(PowerLossReset, "ERROR: The processor has experienced a reset due to power loss");
printDebugIfActive(SwAssertion, "ERROR: An internal software assertion has failed");
printDebugIfActive(CrashEvent, "ERROR: crash signal is detected by HVP");
printDebugIfActive(OverDchgCurrentFault, "ERROR: Pack discharge current is above the safe max discharge current limit!");
printDebugIfActive(OverDchgCurrentFault,
"ERROR: Pack discharge current is above the safe max discharge current limit!");
printDebugIfActive(OverChargeCurrentFault, "ERROR: Pack charge current is above the safe max charge current limit!");
printDebugIfActive(OverCurrentFault, "ERROR: Pack current (discharge or charge) is above max current limit!");
printDebugIfActive(OverTemperatureFault, "ERROR: A pack module temperature is above the max temperature limit!");
@ -568,7 +596,8 @@ void printFaultCodesIfActive(){
printDebugIfActive(VerSupplyFault, "ERROR: Energy reserve voltage supply is below minimum voltage threshold");
printDebugIfActive(HvilFault, "ERROR: High Voltage Inter Lock fault is detected");
printDebugIfActive(BmsHvsMiaFault, "ERROR: BMS node is mia on HVS or HVI CAN");
printDebugIfActive(PackVoltMismatchFault, "ERROR: Pack voltage doesn't match approximately with sum of brick voltages");
printDebugIfActive(PackVoltMismatchFault,
"ERROR: Pack voltage doesn't match approximately with sum of brick voltages");
//printDebugIfActive(EnsMiaFault, "ERROR: ENS line is not connected to HVC"); //Uncommented due to not affecting usage
printDebugIfActive(PackPosCtrArcFault, "ERROR: HVP detectes series arc at pack contactor");
printDebugIfActive(packNegCtrArcFault, "ERROR: HVP detectes series arc at FC contactor");

View file

@ -1,11 +1,12 @@
#ifndef TESLA_MODEL_3_BATTERY_H
#define TESLA_MODEL_3_BATTERY_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#define ABSOLUTE_MAX_VOLTAGE 4030 // 403.0V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 2450 // 245.0V if battery voltage goes under this, discharging further is disabled
#define ABSOLUTE_MAX_VOLTAGE \
4030 // 403.0V,if battery voltage goes over this, charging is not possible (goes into forced discharge)
#define ABSOLUTE_MIN_VOLTAGE 2450 // 245.0V if battery voltage goes under this, discharging further is disabled
// These parameters need to be mapped for the Inverter
extern uint16_t SOC;
@ -42,8 +43,8 @@ void receive_can_tesla_model_3_battery(CAN_frame_t rx_frame);
void send_can_tesla_model_3_battery();
void printFaultCodesIfActive();
void printDebugIfActive(uint8_t symbol, const char* message);
void print_int_with_units(char *header, int value, char *units);
void print_SOC(char *header, int SOC);
void print_int_with_units(char* header, int value, char* units);
void print_SOC(char* header, int SOC);
uint16_t convert2unsignedInt16(int16_t signed_value);
#endif
#endif

View file

@ -1,38 +1,33 @@
#include "ESP32CAN.h"
#include <Arduino.h>
int ESP32CAN::CANInit()
{
return CAN_init();
int ESP32CAN::CANInit() {
return CAN_init();
}
int ESP32CAN::CANWriteFrame(const CAN_frame_t* p_frame)
{
static unsigned long start_time;
int result = -1;
if(tx_ok){
result = CAN_write_frame(p_frame);
tx_ok = (result == 0) ? true : false;
if(tx_ok == false){
Serial.println("CAN failure! Check wires");
LEDcolor = 3;
start_time = millis();
}
int ESP32CAN::CANWriteFrame(const CAN_frame_t* p_frame) {
static unsigned long start_time;
int result = -1;
if (tx_ok) {
result = CAN_write_frame(p_frame);
tx_ok = (result == 0) ? true : false;
if (tx_ok == false) {
Serial.println("CAN failure! Check wires");
LEDcolor = 3;
start_time = millis();
}
else{
if((millis() - start_time) >= 2000){
tx_ok = true;
LEDcolor = 0;
}
} else {
if ((millis() - start_time) >= 2000) {
tx_ok = true;
LEDcolor = 0;
}
return result;
}
return result;
}
int ESP32CAN::CANStop()
{
return CAN_stop();
int ESP32CAN::CANStop() {
return CAN_stop();
}
int ESP32CAN::CANConfigFilter(const CAN_filter_t* p_filter)
{
return CAN_config_filter(p_filter);
int ESP32CAN::CANConfigFilter(const CAN_filter_t* p_filter) {
return CAN_config_filter(p_filter);
}
ESP32CAN ESP32Can;

View file

@ -1,19 +1,18 @@
#ifndef ESP32CAN_H
#define ESP32CAN_H
#include "../../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
#include "../../lib/ThomasBarth-ESP32-CAN-Driver/CAN.h"
#include "../../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
extern uint8_t LEDcolor;
class ESP32CAN
{
public:
bool tx_ok = true;
int CANInit();
int CANConfigFilter(const CAN_filter_t* p_filter);
int CANWriteFrame(const CAN_frame_t* p_frame);
int CANStop();
void CANSetCfg(CAN_device_t *can_cfg);
class ESP32CAN {
public:
bool tx_ok = true;
int CANInit();
int CANConfigFilter(const CAN_filter_t* p_filter);
int CANWriteFrame(const CAN_frame_t* p_frame);
int CANStop();
void CANSetCfg(CAN_device_t* can_cfg);
};
extern ESP32CAN ESP32Can;

View file

@ -7,23 +7,23 @@
#define CAN_RX_PIN 26
#define CAN_SE_PIN 23
#define RS485_EN_PIN 17 // 17 /RE
#define RS485_TX_PIN 22 // 21
#define RS485_RX_PIN 21 // 22
#define RS485_SE_PIN 19 // 22 /SHDN
#define RS485_EN_PIN 17 // 17 /RE
#define RS485_TX_PIN 22 // 21
#define RS485_RX_PIN 21 // 22
#define RS485_SE_PIN 19 // 22 /SHDN
#ifdef DUAL_CAN
#define MCP2515_SCK 12 // SCK input of MCP2515
#define MCP2515_MOSI 5 // SDI input of MCP2515
#define MCP2515_MISO 34 // SDO output of MCP2515 | Pin 34 is input only, without pullup/down resistors
#define MCP2515_CS 18 // CS input of MCP2515
#define MCP2515_INT 35 // INT output of MCP2515 | | Pin 35 is input only, without pullup/down resistors
#define MCP2515_SCK 12 // SCK input of MCP2515
#define MCP2515_MOSI 5 // SDI input of MCP2515
#define MCP2515_MISO 34 // SDO output of MCP2515 | Pin 34 is input only, without pullup/down resistors
#define MCP2515_CS 18 // CS input of MCP2515
#define MCP2515_INT 35 // INT output of MCP2515 | | Pin 35 is input only, without pullup/down resistors
#endif
#ifdef CONTACTOR_CONTROL
#define POSITIVE_CONTACTOR_PIN 32
#define NEGATIVE_CONTACTOR_PIN 33
#define PRECHARGE_PIN 25
#define POSITIVE_CONTACTOR_PIN 32
#define NEGATIVE_CONTACTOR_PIN 33
#define PRECHARGE_PIN 25
#endif
#define SD_MISO_PIN 2
@ -32,4 +32,4 @@
#define SD_CS_PIN 13
#define WS2812_PIN 4
#endif
#endif

View file

@ -52,127 +52,124 @@ static uint32_t t1l_ticks = 0;
// libraries. Redefine as 1 to restrict Neopixels to only a single channel.
#define ADAFRUIT_RMT_CHANNEL_MAX RMT_CHANNEL_MAX
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_HW_BASE (&RMT)
bool rmt_reserved_channels[ADAFRUIT_RMT_CHANNEL_MAX];
static void IRAM_ATTR ws2812_rmt_adapter(const void *src, rmt_item32_t *dest, size_t src_size,
size_t wanted_num, size_t *translated_size, size_t *item_num)
{
if (src == NULL || dest == NULL) {
*translated_size = 0;
*item_num = 0;
return;
static void IRAM_ATTR ws2812_rmt_adapter(const void* src, rmt_item32_t* dest, size_t src_size, size_t wanted_num,
size_t* translated_size, size_t* item_num) {
if (src == NULL || dest == NULL) {
*translated_size = 0;
*item_num = 0;
return;
}
const rmt_item32_t bit0 = {{{t0h_ticks, 1, t0l_ticks, 0}}}; //Logical 0
const rmt_item32_t bit1 = {{{t1h_ticks, 1, t1l_ticks, 0}}}; //Logical 1
size_t size = 0;
size_t num = 0;
uint8_t* psrc = (uint8_t*)src;
rmt_item32_t* pdest = dest;
while (size < src_size && num < wanted_num) {
for (int i = 0; i < 8; i++) {
// MSB first
if (*psrc & (1 << (7 - i))) {
pdest->val = bit1.val;
} else {
pdest->val = bit0.val;
}
num++;
pdest++;
}
const rmt_item32_t bit0 = {{{ t0h_ticks, 1, t0l_ticks, 0 }}}; //Logical 0
const rmt_item32_t bit1 = {{{ t1h_ticks, 1, t1l_ticks, 0 }}}; //Logical 1
size_t size = 0;
size_t num = 0;
uint8_t *psrc = (uint8_t *)src;
rmt_item32_t *pdest = dest;
while (size < src_size && num < wanted_num) {
for (int i = 0; i < 8; i++) {
// MSB first
if (*psrc & (1 << (7 - i))) {
pdest->val = bit1.val;
} else {
pdest->val = bit0.val;
}
num++;
pdest++;
}
size++;
psrc++;
}
*translated_size = size;
*item_num = num;
size++;
psrc++;
}
*translated_size = size;
*item_num = num;
}
void espShow(uint8_t pin, uint8_t *pixels, uint32_t numBytes, boolean is800KHz) {
// Reserve channel
rmt_channel_t channel = ADAFRUIT_RMT_CHANNEL_MAX;
for (size_t i = 0; i < ADAFRUIT_RMT_CHANNEL_MAX; i++) {
if (!rmt_reserved_channels[i]) {
rmt_reserved_channels[i] = true;
channel = i;
break;
}
}
if (channel == ADAFRUIT_RMT_CHANNEL_MAX) {
// Ran out of channels!
return;
void espShow(uint8_t pin, uint8_t* pixels, uint32_t numBytes, boolean is800KHz) {
// Reserve channel
rmt_channel_t channel = ADAFRUIT_RMT_CHANNEL_MAX;
for (size_t i = 0; i < ADAFRUIT_RMT_CHANNEL_MAX; i++) {
if (!rmt_reserved_channels[i]) {
rmt_reserved_channels[i] = true;
channel = i;
break;
}
}
if (channel == ADAFRUIT_RMT_CHANNEL_MAX) {
// Ran out of channels!
return;
}
#if defined(HAS_ESP_IDF_4)
rmt_config_t config = RMT_DEFAULT_CONFIG_TX(pin, channel);
config.clk_div = 2;
rmt_config_t config = RMT_DEFAULT_CONFIG_TX(pin, channel);
config.clk_div = 2;
#else
// Match default TX config from ESP-IDF version 3.4
rmt_config_t config = {
.rmt_mode = RMT_MODE_TX,
.channel = channel,
.gpio_num = pin,
.clk_div = 2,
.mem_block_num = 1,
.tx_config = {
.carrier_freq_hz = 38000,
.carrier_level = RMT_CARRIER_LEVEL_HIGH,
.idle_level = RMT_IDLE_LEVEL_LOW,
.carrier_duty_percent = 33,
.carrier_en = false,
.loop_en = false,
.idle_output_en = true,
}
};
// Match default TX config from ESP-IDF version 3.4
rmt_config_t config = {.rmt_mode = RMT_MODE_TX,
.channel = channel,
.gpio_num = pin,
.clk_div = 2,
.mem_block_num = 1,
.tx_config = {
.carrier_freq_hz = 38000,
.carrier_level = RMT_CARRIER_LEVEL_HIGH,
.idle_level = RMT_IDLE_LEVEL_LOW,
.carrier_duty_percent = 33,
.carrier_en = false,
.loop_en = false,
.idle_output_en = true,
}};
#endif
rmt_config(&config);
rmt_driver_install(config.channel, 0, 0);
rmt_config(&config);
rmt_driver_install(config.channel, 0, 0);
// Convert NS timings to ticks
uint32_t counter_clk_hz = 0;
// Convert NS timings to ticks
uint32_t counter_clk_hz = 0;
#if defined(HAS_ESP_IDF_4)
rmt_get_counter_clock(channel, &counter_clk_hz);
rmt_get_counter_clock(channel, &counter_clk_hz);
#else
// this emulates the rmt_get_counter_clock() function from ESP-IDF 3.4
if (RMT_LL_HW_BASE->conf_ch[config.channel].conf1.ref_always_on == RMT_BASECLK_REF) {
uint32_t div_cnt = RMT_LL_HW_BASE->conf_ch[config.channel].conf0.div_cnt;
uint32_t div = div_cnt == 0 ? 256 : div_cnt;
counter_clk_hz = REF_CLK_FREQ / (div);
} else {
uint32_t div_cnt = RMT_LL_HW_BASE->conf_ch[config.channel].conf0.div_cnt;
uint32_t div = div_cnt == 0 ? 256 : div_cnt;
counter_clk_hz = APB_CLK_FREQ / (div);
}
// this emulates the rmt_get_counter_clock() function from ESP-IDF 3.4
if (RMT_LL_HW_BASE->conf_ch[config.channel].conf1.ref_always_on == RMT_BASECLK_REF) {
uint32_t div_cnt = RMT_LL_HW_BASE->conf_ch[config.channel].conf0.div_cnt;
uint32_t div = div_cnt == 0 ? 256 : div_cnt;
counter_clk_hz = REF_CLK_FREQ / (div);
} else {
uint32_t div_cnt = RMT_LL_HW_BASE->conf_ch[config.channel].conf0.div_cnt;
uint32_t div = div_cnt == 0 ? 256 : div_cnt;
counter_clk_hz = APB_CLK_FREQ / (div);
}
#endif
// NS to tick converter
float ratio = (float)counter_clk_hz / 1e9;
// NS to tick converter
float ratio = (float)counter_clk_hz / 1e9;
if (is800KHz) {
t0h_ticks = (uint32_t)(ratio * WS2812_T0H_NS);
t0l_ticks = (uint32_t)(ratio * WS2812_T0L_NS);
t1h_ticks = (uint32_t)(ratio * WS2812_T1H_NS);
t1l_ticks = (uint32_t)(ratio * WS2812_T1L_NS);
} else {
t0h_ticks = (uint32_t)(ratio * WS2811_T0H_NS);
t0l_ticks = (uint32_t)(ratio * WS2811_T0L_NS);
t1h_ticks = (uint32_t)(ratio * WS2811_T1H_NS);
t1l_ticks = (uint32_t)(ratio * WS2811_T1L_NS);
}
if (is800KHz) {
t0h_ticks = (uint32_t)(ratio * WS2812_T0H_NS);
t0l_ticks = (uint32_t)(ratio * WS2812_T0L_NS);
t1h_ticks = (uint32_t)(ratio * WS2812_T1H_NS);
t1l_ticks = (uint32_t)(ratio * WS2812_T1L_NS);
} else {
t0h_ticks = (uint32_t)(ratio * WS2811_T0H_NS);
t0l_ticks = (uint32_t)(ratio * WS2811_T0L_NS);
t1h_ticks = (uint32_t)(ratio * WS2811_T1H_NS);
t1l_ticks = (uint32_t)(ratio * WS2811_T1L_NS);
}
// Initialize automatic timing translator
rmt_translator_init(config.channel, ws2812_rmt_adapter);
// Initialize automatic timing translator
rmt_translator_init(config.channel, ws2812_rmt_adapter);
// Write and wait to finish
rmt_write_sample(config.channel, pixels, (size_t)numBytes, true);
rmt_wait_tx_done(config.channel, pdMS_TO_TICKS(100));
// Write and wait to finish
rmt_write_sample(config.channel, pixels, (size_t)numBytes, true);
rmt_wait_tx_done(config.channel, pdMS_TO_TICKS(100));
// Free channel again
rmt_driver_uninstall(config.channel);
rmt_reserved_channels[channel] = false;
// Free channel again
rmt_driver_uninstall(config.channel);
rmt_reserved_channels[channel] = false;
gpio_set_direction(pin, GPIO_MODE_OUTPUT);
gpio_set_direction(pin, GPIO_MODE_OUTPUT);
}
#endif

View file

@ -6,179 +6,168 @@
extern uint16_t mbPV[MBPV_MAX];
// Server function to handle FC 0x03
ModbusMessage FC03(ModbusMessage request)
{
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t addr = 0; // Start address
uint16_t words = 0; // # of words requested
request.get(2, addr); // read address from request
request.get(4, words); // read # of words from request
char debugString[1000];
ModbusMessage FC03(ModbusMessage request) {
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t addr = 0; // Start address
uint16_t words = 0; // # of words requested
request.get(2, addr); // read address from request
request.get(4, words); // read # of words from request
char debugString[1000];
LOG_D("FC03 received: read %d words @ %d\r\n", words, addr);
// Address overflow?
if ((addr + words) > MBPV_MAX)
{
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
// Set up response
response.add(request.getServerID(), request.getFunctionCode(), (uint8_t)(words * 2));
sprintf(debugString, "Read : ");
for (uint8_t i = 0; i < words; ++i)
{
// send increasing data values
response.add((uint16_t)(mbPV[addr + i]));
sprintf(debugString + strlen(debugString), "%i ", mbPV[addr + i]);
}
LOG_V("%s\r\n", debugString);
LOG_D("FC03 received: read %d words @ %d\r\n", words, addr);
// Address overflow?
if ((addr + words) > MBPV_MAX) {
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
// Set up response
response.add(request.getServerID(), request.getFunctionCode(), (uint8_t)(words * 2));
sprintf(debugString, "Read : ");
for (uint8_t i = 0; i < words; ++i) {
// send increasing data values
response.add((uint16_t)(mbPV[addr + i]));
sprintf(debugString + strlen(debugString), "%i ", mbPV[addr + i]);
}
LOG_V("%s\r\n", debugString);
return response;
}
// Server function to handle FC 0x06
ModbusMessage FC06(ModbusMessage request)
{
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t addr = 0; // Start address
uint16_t val = 0; // value to write
request.get(2, addr); // read address from request
request.get(4, val); // read # of words from request
ModbusMessage FC06(ModbusMessage request) {
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t addr = 0; // Start address
uint16_t val = 0; // value to write
request.get(2, addr); // read address from request
request.get(4, val); // read # of words from request
LOG_D("FC06 received: write 1 word @ %d\r\n", addr);
LOG_D("FC06 received: write 1 word @ %d\r\n", addr);
// Address overflow?
if ((addr) > MBPV_MAX)
{
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
// Do the write
mbPV[addr] = val;
LOG_V("Write : %i", val);
// Set up response
response.add(request.getServerID(), request.getFunctionCode(), mbPV[addr]);
// Address overflow?
if ((addr) > MBPV_MAX) {
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
// Do the write
mbPV[addr] = val;
LOG_V("Write : %i", val);
// Set up response
response.add(request.getServerID(), request.getFunctionCode(), mbPV[addr]);
return response;
}
// Server function to handle FC 0x10 (FC16)
ModbusMessage FC16(ModbusMessage request)
{
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t addr = 0; // Start address
uint16_t words = 0; // total words to write
uint8_t bytes = 0; // # of data bytes in request
uint16_t val = 0; // value to be written
request.get(2, addr); // read address from request
request.get(4, words); // read # of words from request
request.get(6, bytes); // read # of data bytes from request (seems redundant with # of words)
char debugString[1000];
ModbusMessage FC16(ModbusMessage request) {
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t addr = 0; // Start address
uint16_t words = 0; // total words to write
uint8_t bytes = 0; // # of data bytes in request
uint16_t val = 0; // value to be written
request.get(2, addr); // read address from request
request.get(4, words); // read # of words from request
request.get(6, bytes); // read # of data bytes from request (seems redundant with # of words)
char debugString[1000];
LOG_D("FC16 received: write %d words @ %d\r\n", words, addr);
LOG_D("FC16 received: write %d words @ %d\r\n", words, addr);
// # of registers proper?
if ((bytes != (words * 2)) // byte count in request must match # of words in request
|| (words > 123)) // can't support more than this in request packet
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_VALUE);
LOG_D("ERROR - ILLEGAL DATA VALUE\r\n");
return response;
}
// Address overflow?
if ((addr + words) > MBPV_MAX)
{
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
// Do the writes
sprintf(debugString, "Write : ");
for (uint8_t i = 0; i < words; ++i)
{
request.get(7 + (i * 2), val); //data starts at byte 6 in request packet
mbPV[addr + i] = val;
sprintf(debugString + strlen(debugString), "%i ", mbPV[addr + i]);
}
LOG_V("%s\r\n", debugString);
// Set up response
response.add(request.getServerID(), request.getFunctionCode(), addr, words);
// # of registers proper?
if ((bytes != (words * 2)) // byte count in request must match # of words in request
|| (words > 123)) // can't support more than this in request packet
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_VALUE);
LOG_D("ERROR - ILLEGAL DATA VALUE\r\n");
return response;
}
// Address overflow?
if ((addr + words) > MBPV_MAX) {
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
// Do the writes
sprintf(debugString, "Write : ");
for (uint8_t i = 0; i < words; ++i) {
request.get(7 + (i * 2), val); //data starts at byte 6 in request packet
mbPV[addr + i] = val;
sprintf(debugString + strlen(debugString), "%i ", mbPV[addr + i]);
}
LOG_V("%s\r\n", debugString);
// Set up response
response.add(request.getServerID(), request.getFunctionCode(), addr, words);
return response;
}
// Server function to handle FC 0x17 (FC23)
ModbusMessage FC23(ModbusMessage request)
{
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t read_addr = 0; // Start address for read
uint16_t read_words = 0; // # of words requested for read
uint16_t write_addr = 0; // Start address for write
uint16_t write_words = 0; // total words to write
uint8_t write_bytes = 0; // # of data bytes in write request
uint16_t write_val = 0; // value to be written
request.get(2, read_addr); // read address from request
request.get(4, read_words); // read # of words from request
request.get(6, write_addr); // read address from request
request.get(8, write_words); // read # of words from request
request.get(10, write_bytes); // read # of data bytes from request (seems redundant with # of words)
char debugString[1000];
ModbusMessage FC23(ModbusMessage request) {
//Serial.println(request);
ModbusMessage response; // The Modbus message we are going to give back
uint16_t read_addr = 0; // Start address for read
uint16_t read_words = 0; // # of words requested for read
uint16_t write_addr = 0; // Start address for write
uint16_t write_words = 0; // total words to write
uint8_t write_bytes = 0; // # of data bytes in write request
uint16_t write_val = 0; // value to be written
request.get(2, read_addr); // read address from request
request.get(4, read_words); // read # of words from request
request.get(6, write_addr); // read address from request
request.get(8, write_words); // read # of words from request
request.get(10, write_bytes); // read # of data bytes from request (seems redundant with # of words)
char debugString[1000];
LOG_D("FC23 received: write %d @ %d, read %d @ %d\r\n", write_words, write_addr, read_words, read_addr);
// ERROR CHECKS
// # of registers proper?
if ((write_bytes != (write_words * 2)) // byte count in request must match # of words in request
|| (write_words > 121) // can't fit more than this in the packet for FC23
|| (read_words > 125)) // can't fit more than this in the response packet
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_VALUE);
LOG_D("ERROR - ILLEGAL DATA VALUE\r\n");
return response;
}
// Address overflow?
if (((write_addr + write_words) > MBPV_MAX) || ((read_addr + read_words) > MBPV_MAX))
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
//WRITE SECTION - write is done before read for FC23
// Do the writes
sprintf(debugString, "Write: ");
for (uint8_t i = 0; i < write_words; ++i)
{
request.get(11 + (i * 2), write_val); //data starts at byte 6 in request packet
mbPV[write_addr + i] = write_val;
sprintf(debugString + strlen(debugString), "%i ", mbPV[write_addr + i]);
}
LOG_V("%s\r\n", debugString);
// READ SECTION
// Set up response
sprintf(debugString, "Read: ");
response.add(request.getServerID(), request.getFunctionCode(), (uint8_t)(read_words * 2));
for (uint8_t i = 0; i < read_words; ++i)
{
// send increasing data values
response.add((uint16_t)(mbPV[read_addr + i]));
sprintf(debugString + strlen(debugString), "%i ", mbPV[read_addr + i]);
}
LOG_V("%s\r\n", debugString);
LOG_D("FC23 received: write %d @ %d, read %d @ %d\r\n", write_words, write_addr, read_words, read_addr);
// ERROR CHECKS
// # of registers proper?
if ((write_bytes != (write_words * 2)) // byte count in request must match # of words in request
|| (write_words > 121) // can't fit more than this in the packet for FC23
|| (read_words > 125)) // can't fit more than this in the response packet
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_VALUE);
LOG_D("ERROR - ILLEGAL DATA VALUE\r\n");
return response;
}
}
// Address overflow?
if (((write_addr + write_words) > MBPV_MAX) ||
((read_addr + read_words) > MBPV_MAX)) { // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
LOG_D("ERROR - ILLEGAL DATA ADDRESS\r\n");
return response;
}
//WRITE SECTION - write is done before read for FC23
// Do the writes
sprintf(debugString, "Write: ");
for (uint8_t i = 0; i < write_words; ++i) {
request.get(11 + (i * 2), write_val); //data starts at byte 6 in request packet
mbPV[write_addr + i] = write_val;
sprintf(debugString + strlen(debugString), "%i ", mbPV[write_addr + i]);
}
LOG_V("%s\r\n", debugString);
// READ SECTION
// Set up response
sprintf(debugString, "Read: ");
response.add(request.getServerID(), request.getFunctionCode(), (uint8_t)(read_words * 2));
for (uint8_t i = 0; i < read_words; ++i) {
// send increasing data values
response.add((uint16_t)(mbPV[read_addr + i]));
sprintf(debugString + strlen(debugString), "%i ", mbPV[read_addr + i]);
}
LOG_V("%s\r\n", debugString);
return response;
}

View file

@ -1,9 +1,8 @@
#include "../../lib/eModbus-eModbus/ModbusServerRTU.h"
#define MBTCP_ID 21 // modbus TCP server ID
#define MBTCP_ID 21 // modbus TCP server ID
#define MBPV_MAX 30000
ModbusMessage FC03(ModbusMessage request);
ModbusMessage FC06(ModbusMessage request);
ModbusMessage FC16(ModbusMessage request);

View file

@ -3,27 +3,101 @@
#include "../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
/* Do not change code below unless you are sure what you are doing */
static unsigned long previousMillis2s = 0; // will store last time a 2s CAN Message was send
static unsigned long previousMillis10s = 0; // will store last time a 10s CAN Message was send
static unsigned long previousMillis60s = 0; // will store last time a 60s CAN Message was send
static const int interval2s = 2000; // interval (ms) at which send CAN Messages
static const int interval10s = 10000; // interval (ms) at which send CAN Messages
static const int interval60s = 60000; // interval (ms) at which send CAN Messages
static unsigned long previousMillis2s = 0; // will store last time a 2s CAN Message was send
static unsigned long previousMillis10s = 0; // will store last time a 10s CAN Message was send
static unsigned long previousMillis60s = 0; // will store last time a 60s CAN Message was send
static const int interval2s = 2000; // interval (ms) at which send CAN Messages
static const int interval10s = 10000; // interval (ms) at which send CAN Messages
static const int interval60s = 60000; // interval (ms) at which send CAN Messages
//Startup messages
const CAN_frame_t BYD_250 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x250,.data = {0x03, 0x16, 0x00, 0x66, (uint8_t)((BATTERY_WH_MAX/100) >> 8), (uint8_t)(BATTERY_WH_MAX/100), 0x02, 0x09}}; //3.16 FW , Capacity kWh byte4&5 (example 24kWh = 240)
const CAN_frame_t BYD_290 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x290,.data = {0x06, 0x37, 0x10, 0xD9, 0x00, 0x00, 0x00, 0x00}};
const CAN_frame_t BYD_2D0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x2D0,.data = {0x00, 0x42, 0x59, 0x44, 0x00, 0x00, 0x00, 0x00}}; //BYD
const CAN_frame_t BYD_3D0_0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x3D0,.data = {0x00, 0x42, 0x61, 0x74, 0x74, 0x65, 0x72, 0x79}}; //Battery
const CAN_frame_t BYD_3D0_1 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x3D0,.data = {0x01, 0x2D, 0x42, 0x6F, 0x78, 0x20, 0x50, 0x72}}; //-Box Pr
const CAN_frame_t BYD_3D0_2 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x3D0,.data = {0x02, 0x65, 0x6D, 0x69, 0x75, 0x6D, 0x20, 0x48}}; //emium H
const CAN_frame_t BYD_3D0_3 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x3D0,.data = {0x03, 0x56, 0x53, 0x00, 0x00, 0x00, 0x00, 0x00}}; //VS
const CAN_frame_t BYD_250 = {
.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x250,
.data = {0x03, 0x16, 0x00, 0x66, (uint8_t)((BATTERY_WH_MAX / 100) >> 8), (uint8_t)(BATTERY_WH_MAX / 100), 0x02,
0x09}}; //3.16 FW , Capacity kWh byte4&5 (example 24kWh = 240)
const CAN_frame_t BYD_290 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x290,
.data = {0x06, 0x37, 0x10, 0xD9, 0x00, 0x00, 0x00, 0x00}};
const CAN_frame_t BYD_2D0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x2D0,
.data = {0x00, 0x42, 0x59, 0x44, 0x00, 0x00, 0x00, 0x00}}; //BYD
const CAN_frame_t BYD_3D0_0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x3D0,
.data = {0x00, 0x42, 0x61, 0x74, 0x74, 0x65, 0x72, 0x79}}; //Battery
const CAN_frame_t BYD_3D0_1 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x3D0,
.data = {0x01, 0x2D, 0x42, 0x6F, 0x78, 0x20, 0x50, 0x72}}; //-Box Pr
const CAN_frame_t BYD_3D0_2 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x3D0,
.data = {0x02, 0x65, 0x6D, 0x69, 0x75, 0x6D, 0x20, 0x48}}; //emium H
const CAN_frame_t BYD_3D0_3 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x3D0,
.data = {0x03, 0x56, 0x53, 0x00, 0x00, 0x00, 0x00, 0x00}}; //VS
//Actual content messages
CAN_frame_t BYD_110 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x110,.data = {0x01, 0x90, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t BYD_150 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x150,.data = {0x00, 0x00, 0x00, 0x00, 0x10, 0x27, 0x00, 0x00}};
CAN_frame_t BYD_190 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x190,.data = {0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t BYD_1D0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x1D0,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08}};
CAN_frame_t BYD_210 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x210,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t BYD_110 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x110,
.data = {0x01, 0x90, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t BYD_150 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x150,
.data = {0x00, 0x00, 0x00, 0x00, 0x10, 0x27, 0x00, 0x00}};
CAN_frame_t BYD_190 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x190,
.data = {0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t BYD_1D0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x1D0,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08}};
CAN_frame_t BYD_210 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x210,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static int discharge_current = 0;
static int charge_current = 0;
@ -34,27 +108,27 @@ static int inverter_voltage = 0;
static int inverter_SOC = 0;
static long inverter_timestamp = 0;
void update_values_can_byd()
{ //This function maps all the values fetched from battery CAN to the correct CAN messages
void update_values_can_byd() { //This function maps all the values fetched from battery CAN to the correct CAN messages
//Calculate values
charge_current = ((max_target_charge_power*10)/max_volt_byd_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
charge_current = ((max_target_charge_power * 10) /
max_volt_byd_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
//The above calculation results in (30 000*10)/3700=81A
charge_current = (charge_current*10); //Value needs a decimal before getting sent to inverter (81.0A)
if(charge_current > MAXCHARGEAMP)
{
charge_current = MAXCHARGEAMP; //Cap the value to the max allowed Amp. Some inverters cannot handle large values.
charge_current = (charge_current * 10); //Value needs a decimal before getting sent to inverter (81.0A)
if (charge_current > MAXCHARGEAMP) {
charge_current = MAXCHARGEAMP; //Cap the value to the max allowed Amp. Some inverters cannot handle large values.
}
discharge_current = ((max_target_discharge_power*10)/max_volt_byd_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
discharge_current = ((max_target_discharge_power * 10) /
max_volt_byd_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
//The above calculation results in (30 000*10)/3700=81A
discharge_current = (discharge_current*10); //Value needs a decimal before getting sent to inverter (81.0A)
if(discharge_current > MAXDISCHARGEAMP)
{
discharge_current = MAXDISCHARGEAMP; //Cap the value to the max allowed Amp. Some inverters cannot handle large values.
discharge_current = (discharge_current * 10); //Value needs a decimal before getting sent to inverter (81.0A)
if (discharge_current > MAXDISCHARGEAMP) {
discharge_current =
MAXDISCHARGEAMP; //Cap the value to the max allowed Amp. Some inverters cannot handle large values.
}
temperature_average = ((temperature_max + temperature_min)/2);
temperature_average = ((temperature_max + temperature_min) / 2);
//Map values to CAN messages
//Maxvoltage (eg 400.0V = 4000 , 16bits long)
BYD_110.data.u8[0] = (max_volt_byd_can >> 8);
@ -100,50 +174,44 @@ void update_values_can_byd()
BYD_210.data.u8[3] = (temperature_min & 0x00FF);
}
void receive_can_byd(CAN_frame_t rx_frame)
{
switch (rx_frame.MsgID)
{
case 0x151: //Message originating from BYD HVS compatible inverter. Reply with CAN identifier!
if(rx_frame.data.u8[0] & 0x01)
{
void receive_can_byd(CAN_frame_t rx_frame) {
switch (rx_frame.MsgID) {
case 0x151: //Message originating from BYD HVS compatible inverter. Reply with CAN identifier!
if (rx_frame.data.u8[0] & 0x01) {
send_intial_data();
}
break;
break;
case 0x091:
inverter_voltage = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.1;
break;
break;
case 0x0D1:
inverter_SOC = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.1;
break;
break;
case 0x111:
inverter_timestamp = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) | (rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]);
break;
inverter_timestamp = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) | (rx_frame.data.u8[1] << 8) |
rx_frame.data.u8[0]);
break;
default:
break;
break;
}
}
void send_can_byd()
{
void send_can_byd() {
unsigned long currentMillis = millis();
// Send initial CAN data once on bootup
if (!initialDataSent)
{
if (!initialDataSent) {
send_intial_data();
initialDataSent = 1;
}
// Send 2s CAN Message
if (currentMillis - previousMillis2s >= interval2s)
{
if (currentMillis - previousMillis2s >= interval2s) {
previousMillis2s = currentMillis;
ESP32Can.CANWriteFrame(&BYD_110);
}
// Send 10s CAN Message
if (currentMillis - previousMillis10s >= interval10s)
{
if (currentMillis - previousMillis10s >= interval10s) {
previousMillis10s = currentMillis;
ESP32Can.CANWriteFrame(&BYD_150);
@ -152,17 +220,15 @@ void send_can_byd()
//Serial.println("CAN 10s done");
}
//Send 60s message
if (currentMillis - previousMillis60s >= interval60s)
{
if (currentMillis - previousMillis60s >= interval60s) {
previousMillis60s = currentMillis;
ESP32Can.CANWriteFrame(&BYD_190);
ESP32Can.CANWriteFrame(&BYD_190);
//Serial.println("CAN 60s done");
}
}
void send_intial_data()
{
void send_intial_data() {
ESP32Can.CANWriteFrame(&BYD_250);
ESP32Can.CANWriteFrame(&BYD_290);
ESP32Can.CANWriteFrame(&BYD_2D0);

View file

@ -1,8 +1,8 @@
#ifndef BYD_CAN_H
#define BYD_CAN_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
extern uint16_t SOC;
extern uint16_t StateOfHealth;
@ -33,4 +33,4 @@ void send_can_byd();
void receive_can_byd(CAN_frame_t rx_frame);
void send_intial_data();
#endif
#endif

View file

@ -1,21 +1,23 @@
#include "BYD-MODBUS.h"
void update_modbus_registers_byd() {
//Updata for ModbusRTU Server for BYD
handle_update_data_modbusp201_byd();
handle_update_data_modbusp301_byd();
//Updata for ModbusRTU Server for BYD
handle_update_data_modbusp201_byd();
handle_update_data_modbusp301_byd();
}
void handle_static_data_modbus_byd() {
// Store the data into the array
static uint16_t si_data[] = { 21321, 1 };
static uint16_t byd_data[] = { 16985, 17408, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
static uint16_t battery_data[] = { 16985, 17440, 16993, 29812, 25970, 31021, 17007, 30752, 20594, 25965, 26997, 27936, 18518, 0, 0, 0 };
static uint16_t volt_data[] = { 13614, 12288, 0, 0, 0, 0, 0, 0, 13102, 12598, 0, 0, 0, 0, 0, 0 };
static uint16_t serial_data[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
static uint16_t static_data[] = { 1, 0 };
static uint16_t* data_array_pointers[] = { si_data, byd_data, battery_data, volt_data, serial_data, static_data };
static uint16_t data_sizes[] = { sizeof(si_data), sizeof(byd_data), sizeof(battery_data), sizeof(volt_data), sizeof(serial_data), sizeof(static_data) };
static uint16_t si_data[] = {21321, 1};
static uint16_t byd_data[] = {16985, 17408, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
static uint16_t battery_data[] = {16985, 17440, 16993, 29812, 25970, 31021, 17007, 30752,
20594, 25965, 26997, 27936, 18518, 0, 0, 0};
static uint16_t volt_data[] = {13614, 12288, 0, 0, 0, 0, 0, 0, 13102, 12598, 0, 0, 0, 0, 0, 0};
static uint16_t serial_data[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
static uint16_t static_data[] = {1, 0};
static uint16_t* data_array_pointers[] = {si_data, byd_data, battery_data, volt_data, serial_data, static_data};
static uint16_t data_sizes[] = {sizeof(si_data), sizeof(byd_data), sizeof(battery_data),
sizeof(volt_data), sizeof(serial_data), sizeof(static_data)};
static uint16_t i = 100;
for (uint8_t arr_idx = 0; arr_idx < sizeof(data_array_pointers) / sizeof(uint16_t*); arr_idx++) {
uint16_t data_size = data_sizes[arr_idx];
@ -27,19 +29,25 @@ void handle_static_data_modbus_byd() {
void handle_update_data_modbusp201_byd() {
// Store the data into the array
static uint16_t system_data[13];
system_data[0] = 0; // Id.: p201 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[1] = 0; // Id.: p202 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[2] = (capacity_Wh_startup); // Id.: p203 Value.: 32000 Scaled value.: 32kWh Comment.: Capacity rated, maximum value is 60000 (60kWh)
system_data[3] = (max_power); // Id.: p204 Value.: 32000 Scaled value.: 32kWh Comment.: Nominal capacity
system_data[4] = (max_power); // Id.: p205 Value.: 14500 Scaled value.: 30,42kW Comment.: Max Charge/Discharge Power=10.24kW (lowest value of 204 and 205 will be enforced by Gen24)
system_data[5] = (max_volt_modbus_byd); // Id.: p206 Value.: 3667 Scaled value.: 362,7VDC Comment.: Max Voltage, if higher charging is not possible (goes into forced discharge)
system_data[6] = (min_volt_modbus_byd); // Id.: p207 Value.: 2776 Scaled value.: 277,6VDC Comment.: Min Voltage, if lower Gen24 disables battery
system_data[7] = 53248; // Id.: p208 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Charge power?
system_data[8] = 10; // Id.: p209 Value.: 10 Scaled value.: 10 Comment.: Always 10
system_data[9] = 53248; // Id.: p210 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Discharge power?
system_data[10] = 10; // Id.: p211 Value.: 10 Scaled value.: 10 Comment.: Always 10
system_data[11] = 0; // Id.: p212 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[12] = 0; // Id.: p213 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[0] = 0; // Id.: p201 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[1] = 0; // Id.: p202 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[2] =
(capacity_Wh_startup); // Id.: p203 Value.: 32000 Scaled value.: 32kWh Comment.: Capacity rated, maximum value is 60000 (60kWh)
system_data[3] = (max_power); // Id.: p204 Value.: 32000 Scaled value.: 32kWh Comment.: Nominal capacity
system_data[4] =
(max_power); // Id.: p205 Value.: 14500 Scaled value.: 30,42kW Comment.: Max Charge/Discharge Power=10.24kW (lowest value of 204 and 205 will be enforced by Gen24)
system_data[5] =
(max_volt_modbus_byd); // Id.: p206 Value.: 3667 Scaled value.: 362,7VDC Comment.: Max Voltage, if higher charging is not possible (goes into forced discharge)
system_data[6] =
(min_volt_modbus_byd); // Id.: p207 Value.: 2776 Scaled value.: 277,6VDC Comment.: Min Voltage, if lower Gen24 disables battery
system_data[7] =
53248; // Id.: p208 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Charge power?
system_data[8] = 10; // Id.: p209 Value.: 10 Scaled value.: 10 Comment.: Always 10
system_data[9] =
53248; // Id.: p210 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Discharge power?
system_data[10] = 10; // Id.: p211 Value.: 10 Scaled value.: 10 Comment.: Always 10
system_data[11] = 0; // Id.: p212 Value.: 0 Scaled value.: 0 Comment.: Always 0
system_data[12] = 0; // Id.: p213 Value.: 0 Scaled value.: 0 Comment.: Always 0
static uint16_t i = 200;
memcpy(&mbPV[i], system_data, sizeof(system_data));
}
@ -47,43 +55,54 @@ void handle_update_data_modbusp201_byd() {
void handle_update_data_modbusp301_byd() {
// Store the data into the array
static uint16_t battery_data[24];
if (battery_current > 0) { //Positive value = Charging
bms_char_dis_status = 2; //Charging
} else if (battery_current < 0) { //Negative value = Discharging
bms_char_dis_status = 1; //Discharging
} else { //battery_current == 0
bms_char_dis_status = 0; //idle
if (battery_current > 0) { //Positive value = Charging
bms_char_dis_status = 2; //Charging
} else if (battery_current < 0) { //Negative value = Discharging
bms_char_dis_status = 1; //Discharging
} else { //battery_current == 0
bms_char_dis_status = 0; //idle
}
if (bms_status == ACTIVE) {
battery_data[8] = battery_voltage; // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
battery_data[8] =
battery_voltage; // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
} else {
battery_data[8] = 0;
}
battery_data[0] = bms_status; // Id.: p301 Value.: 3 Scaled value.: 3 Comment.: status(*): ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
battery_data[1] = 0; // Id.: p302 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[2] = 128 + bms_char_dis_status; // Id.: p303 Value.: 130 Scaled value.: 130 Comment.: mode(*): normal
battery_data[3] = SOC; // Id.: p304 Value.: 1700 Scaled value.: 50% Comment.: SOC: (50% would equal 5000)
battery_data[4] = capacity_Wh; // Id.: p305 Value.: 32000 Scaled value.: 32kWh Comment.: tot cap:
battery_data[5] = remaining_capacity_Wh; // Id.: p306 Value.: 13260 Scaled value.: 13,26kWh Comment.: remaining cap: 7.68kWh
battery_data[6] = max_target_discharge_power; // Id.: p307 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target discharge power: 0W (0W > restricts to no discharge)
battery_data[7] = max_target_charge_power; // Id.: p308 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target charge power: 4.3kW (during charge), both 307&308 can be set (>0) at the same time
battery_data[0] =
bms_status; // Id.: p301 Value.: 3 Scaled value.: 3 Comment.: status(*): ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
battery_data[1] = 0; // Id.: p302 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[2] = 128 + bms_char_dis_status; // Id.: p303 Value.: 130 Scaled value.: 130 Comment.: mode(*): normal
battery_data[3] = SOC; // Id.: p304 Value.: 1700 Scaled value.: 50% Comment.: SOC: (50% would equal 5000)
battery_data[4] = capacity_Wh; // Id.: p305 Value.: 32000 Scaled value.: 32kWh Comment.: tot cap:
battery_data[5] =
remaining_capacity_Wh; // Id.: p306 Value.: 13260 Scaled value.: 13,26kWh Comment.: remaining cap: 7.68kWh
battery_data[6] =
max_target_discharge_power; // Id.: p307 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target discharge power: 0W (0W > restricts to no discharge)
battery_data[7] =
max_target_charge_power; // Id.: p308 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target charge power: 4.3kW (during charge), both 307&308 can be set (>0) at the same time
//Battery_data[8] set previously in function // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
battery_data[9] = 2000; // Id.: p310 Value.: 64121 Scaled value.: 6412,1W Comment.: Current Power to API: if>32768... -(65535-61760)=3775W
battery_data[10] = battery_voltage; // Id.: p311 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage inner: 173.2V (LEAF voltage is in whole volts, need to add a decimal)
battery_data[11] = 2000; // Id.: p312 Value.: 64121 Scaled value.: 6412,1W Comment.: p310
battery_data[12] = temperature_min; // Id.: p313 Value.: 75 Scaled value.: 7,5 Comment.: temp min: 7 degrees (if below 0....65535-t)
battery_data[13] = temperature_max; // Id.: p314 Value.: 95 Scaled value.: 9,5 Comment.: temp max: 9 degrees (if below 0....65535-t)
battery_data[14] = 0; // Id.: p315 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[15] = 0; // Id.: p316 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[16] = 16; // Id.: p317 Value.: 0 Scaled value.: 0 Comment.: counter charge hi
battery_data[17] = 22741; // Id.: p318 Value.: 0 Scaled value.: 0 Comment.: counter charge lo....65536*101+9912 = 6629048 Wh?
battery_data[18] = 0; // Id.: p319 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[19] = 0; // Id.: p320 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[20] = 13; // Id.: p321 Value.: 0 Scaled value.: 0 Comment.: counter discharge hi
battery_data[21] = 52064; // Id.: p322 Value.: 0 Scaled value.: 0 Comment.: counter discharge lo....65536*92+7448 = 6036760 Wh?
battery_data[22] = 230; // Id.: p323 Value.: 0 Scaled value.: 0 Comment.: device temperature (23 degrees)
battery_data[23] = StateOfHealth; // Id.: p324 Value.: 9900 Scaled value.: 99% Comment.: SOH
battery_data[9] =
2000; // Id.: p310 Value.: 64121 Scaled value.: 6412,1W Comment.: Current Power to API: if>32768... -(65535-61760)=3775W
battery_data[10] =
battery_voltage; // Id.: p311 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage inner: 173.2V (LEAF voltage is in whole volts, need to add a decimal)
battery_data[11] = 2000; // Id.: p312 Value.: 64121 Scaled value.: 6412,1W Comment.: p310
battery_data[12] =
temperature_min; // Id.: p313 Value.: 75 Scaled value.: 7,5 Comment.: temp min: 7 degrees (if below 0....65535-t)
battery_data[13] =
temperature_max; // Id.: p314 Value.: 95 Scaled value.: 9,5 Comment.: temp max: 9 degrees (if below 0....65535-t)
battery_data[14] = 0; // Id.: p315 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[15] = 0; // Id.: p316 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[16] = 16; // Id.: p317 Value.: 0 Scaled value.: 0 Comment.: counter charge hi
battery_data[17] =
22741; // Id.: p318 Value.: 0 Scaled value.: 0 Comment.: counter charge lo....65536*101+9912 = 6629048 Wh?
battery_data[18] = 0; // Id.: p319 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[19] = 0; // Id.: p320 Value.: 0 Scaled value.: 0 Comment.: always 0
battery_data[20] = 13; // Id.: p321 Value.: 0 Scaled value.: 0 Comment.: counter discharge hi
battery_data[21] =
52064; // Id.: p322 Value.: 0 Scaled value.: 0 Comment.: counter discharge lo....65536*92+7448 = 6036760 Wh?
battery_data[22] = 230; // Id.: p323 Value.: 0 Scaled value.: 0 Comment.: device temperature (23 degrees)
battery_data[23] = StateOfHealth; // Id.: p324 Value.: 9900 Scaled value.: 99% Comment.: SOH
static uint16_t i = 300;
memcpy(&mbPV[i], battery_data, sizeof(battery_data));
}
}

View file

@ -35,4 +35,4 @@ void handle_static_data_modbus_byd();
void handle_update_data_modbusp201_byd();
void handle_update_data_modbusp301_byd();
void update_modbus_registers_byd();
#endif
#endif

View file

@ -2,31 +2,31 @@
#define INVERTERS_H
#ifdef BYD_CAN
#include "BYD-CAN.h"
#include "BYD-CAN.h"
#endif
#ifdef BYD_MODBUS
#include "BYD-MODBUS.h"
#include "BYD-MODBUS.h"
#endif
#ifdef LUNA2000_MODBUS
#include "LUNA2000-MODBUS.h"
#include "LUNA2000-MODBUS.h"
#endif
#ifdef PYLON_CAN
#include "PYLON-CAN.h"
#include "PYLON-CAN.h"
#endif
#ifdef SMA_CAN
#include "SMA-CAN.h"
#include "SMA-CAN.h"
#endif
#ifdef SOFAR_CAN
#include "SOFAR-CAN.h"
#include "SOFAR-CAN.h"
#endif
#ifdef SOLAX_CAN
#include "SOLAX-CAN.h"
#include "SOLAX-CAN.h"
#endif
#endif
#endif

View file

@ -1,24 +1,23 @@
#include "LUNA2000-MODBUS.h"
void update_modbus_registers_luna2000()
{
//Updata for ModbusRTU Server for Luna2000
handle_update_data_modbus32051();
handle_update_data_modbus39500();
void update_modbus_registers_luna2000() {
//Updata for ModbusRTU Server for Luna2000
handle_update_data_modbus32051();
handle_update_data_modbus39500();
}
void handle_update_data_modbus32051() {
// Store the data into the array
static uint16_t system_data[9];
system_data[0] = 1;
system_data[1] = 534; //Goes between 534-498 depending on SOC
system_data[2] = 110; //Goes between 110- -107 [NOTE, SIGNED VALUE]
system_data[3] = 0; //Goes between 0 and -1 [NOTE, SIGNED VALUE]
system_data[4] = 616; //Goes between 616- -520 [NOTE, SIGNED VALUE]
system_data[5] = temperature_max; //Temperature max?
system_data[6] = temperature_min; //Temperature min?
system_data[7] = (SOC/100); //SOC 0-100%, no decimals
system_data[8] = 98; //Always 98 in logs
system_data[1] = 534; //Goes between 534-498 depending on SOC
system_data[2] = 110; //Goes between 110- -107 [NOTE, SIGNED VALUE]
system_data[3] = 0; //Goes between 0 and -1 [NOTE, SIGNED VALUE]
system_data[4] = 616; //Goes between 616- -520 [NOTE, SIGNED VALUE]
system_data[5] = temperature_max; //Temperature max?
system_data[6] = temperature_min; //Temperature min?
system_data[7] = (SOC / 100); //SOC 0-100%, no decimals
system_data[8] = 98; //Always 98 in logs
static uint16_t i = 2051;
memcpy(&mbPV[i], system_data, sizeof(system_data));
}
@ -27,32 +26,33 @@ void handle_update_data_modbus39500() {
// Store the data into the array
static uint16_t system_data[26];
system_data[0] = 0;
system_data[1] = capacity_Wh_startup; //Capacity? 5000 with 5kWh battery
system_data[1] = capacity_Wh_startup; //Capacity? 5000 with 5kWh battery
system_data[2] = 0;
system_data[3] = capacity_Wh_startup; //Capacity? 5000 with 5kWh battery
system_data[4] = 0;
system_data[5] = 2500; //???
system_data[3] = capacity_Wh_startup; //Capacity? 5000 with 5kWh battery
system_data[4] = 0;
system_data[5] = 2500; //???
system_data[6] = 0;
system_data[7] = 2500; //???
system_data[8] = (SOC/100); //SOC 0-100%, no decimals
system_data[9] = 1; //Running status, equiv to register 37762, 0 = Offline, 1 = Standby,2 = Running, 3 = Fault, 4 = sleep mode
system_data[10] = battery_voltage; //Battery bus voltage (766.5V = 7665)
system_data[11] = 9; //TODO, GOES LOWER WITH LOW SOC
system_data[12] = 0;
system_data[13] = 699; //TODO, GOES LOWER WITH LOW SOC
system_data[14] = 1; //Always 1 in logs
system_data[15] = 18; //Always 18 in logs
system_data[16] = 8066; //TODO, GOES HIGHER WITH LOW SOC (max allowed charge W?)
system_data[17] = 17;
system_data[18] = 44027; //TODO, GOES LOWER WITH LOW SOC
system_data[7] = 2500; //???
system_data[8] = (SOC / 100); //SOC 0-100%, no decimals
system_data[9] =
1; //Running status, equiv to register 37762, 0 = Offline, 1 = Standby,2 = Running, 3 = Fault, 4 = sleep mode
system_data[10] = battery_voltage; //Battery bus voltage (766.5V = 7665)
system_data[11] = 9; //TODO, GOES LOWER WITH LOW SOC
system_data[12] = 0;
system_data[13] = 699; //TODO, GOES LOWER WITH LOW SOC
system_data[14] = 1; //Always 1 in logs
system_data[15] = 18; //Always 18 in logs
system_data[16] = 8066; //TODO, GOES HIGHER WITH LOW SOC (max allowed charge W?)
system_data[17] = 17;
system_data[18] = 44027; //TODO, GOES LOWER WITH LOW SOC
system_data[19] = 0;
system_data[20] = 435; //Always 435 in logs
system_data[20] = 435; //Always 435 in logs
system_data[21] = 0;
system_data[22] = 0;
system_data[23] = 0;
system_data[24] = (SOC/10); //SOC 0-100.0%, 1x decimal
system_data[24] = (SOC / 10); //SOC 0-100.0%, 1x decimal
system_data[25] = 0;
system_data[26] = 1; //Always 1 in logs
system_data[26] = 1; //Always 1 in logs
static uint16_t i = 9500;
memcpy(&mbPV[i], system_data, sizeof(system_data));
}
}

View file

@ -34,4 +34,4 @@ extern uint16_t min_volt_modbus_byd;
void update_modbus_registers_luna2000();
void handle_update_data_modbus32051();
void handle_update_data_modbus39500();
#endif
#endif

View file

@ -2,40 +2,170 @@
#include "../devboard/can/ESP32CAN.h"
#include "../lib/ThomasBarth-ESP32-CAN-Driver/CAN_config.h"
#define SEND_0 //If defined, the messages will have ID ending with 0 (useful for some inverters)
#define SEND_0 //If defined, the messages will have ID ending with 0 (useful for some inverters)
//#define SEND_1 //If defined, the messages will have ID ending with 1 (useful for some inverters)
/* Do not change code below unless you are sure what you are doing */
//Actual content messages
CAN_frame_t PYLON_7310 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7310,.data = {0x01, 0x00, 0x02, 0x01, 0x01, 0x02, 0x00, 0x00}};
CAN_frame_t PYLON_7320 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7320,.data = {0x4B, 0x00, 0x05, 0x0F, 0x2D, 0x00, 0x56, 0x00}};
CAN_frame_t PYLON_7310 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7310,
.data = {0x01, 0x00, 0x02, 0x01, 0x01, 0x02, 0x00, 0x00}};
CAN_frame_t PYLON_7320 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7320,
.data = {0x4B, 0x00, 0x05, 0x0F, 0x2D, 0x00, 0x56, 0x00}};
CAN_frame_t PYLON_4210 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4210,.data = {0xA5, 0x09, 0x30, 0x75, 0x9D, 0x04, 0x2E, 0x64}};
CAN_frame_t PYLON_4220 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4220,.data = {0x8C, 0x0A, 0xE9, 0x07, 0x4A, 0x79, 0x4A, 0x79}};
CAN_frame_t PYLON_4230 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4230,.data = {0xDF, 0x0C, 0xDA, 0x0C, 0x03, 0x00, 0x06, 0x00}};
CAN_frame_t PYLON_4240 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4240,.data = {0x7E, 0x04, 0x62, 0x04, 0x11, 0x00, 0x03, 0x00}};
CAN_frame_t PYLON_4250 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4250,.data = {0x03, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4260 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4260,.data = {0xAC, 0xC7, 0x74, 0x27, 0x03, 0x00, 0x02, 0x00}};
CAN_frame_t PYLON_4270 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4270,.data = {0x7E, 0x04, 0x62, 0x04, 0x05, 0x00, 0x01, 0x00}};
CAN_frame_t PYLON_4280 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4280,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4290 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4290,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4210 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4210,
.data = {0xA5, 0x09, 0x30, 0x75, 0x9D, 0x04, 0x2E, 0x64}};
CAN_frame_t PYLON_4220 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4220,
.data = {0x8C, 0x0A, 0xE9, 0x07, 0x4A, 0x79, 0x4A, 0x79}};
CAN_frame_t PYLON_4230 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4230,
.data = {0xDF, 0x0C, 0xDA, 0x0C, 0x03, 0x00, 0x06, 0x00}};
CAN_frame_t PYLON_4240 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4240,
.data = {0x7E, 0x04, 0x62, 0x04, 0x11, 0x00, 0x03, 0x00}};
CAN_frame_t PYLON_4250 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4250,
.data = {0x03, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4260 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4260,
.data = {0xAC, 0xC7, 0x74, 0x27, 0x03, 0x00, 0x02, 0x00}};
CAN_frame_t PYLON_4270 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4270,
.data = {0x7E, 0x04, 0x62, 0x04, 0x05, 0x00, 0x01, 0x00}};
CAN_frame_t PYLON_4280 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4280,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4290 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4290,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_7311 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7311,.data = {0x01, 0x00, 0x02, 0x01, 0x01, 0x02, 0x00, 0x00}};
CAN_frame_t PYLON_7321 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7321,.data = {0x4B, 0x00, 0x05, 0x0F, 0x2D, 0x00, 0x56, 0x00}};
CAN_frame_t PYLON_7311 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7311,
.data = {0x01, 0x00, 0x02, 0x01, 0x01, 0x02, 0x00, 0x00}};
CAN_frame_t PYLON_7321 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7321,
.data = {0x4B, 0x00, 0x05, 0x0F, 0x2D, 0x00, 0x56, 0x00}};
CAN_frame_t PYLON_4211 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4211,.data = {0xA5, 0x09, 0x30, 0x75, 0x9D, 0x04, 0x2E, 0x64}};
CAN_frame_t PYLON_4221 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4221,.data = {0x8C, 0x0A, 0xE9, 0x07, 0x4A, 0x79, 0x4A, 0x79}};
CAN_frame_t PYLON_4231 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4231,.data = {0xDF, 0x0C, 0xDA, 0x0C, 0x03, 0x00, 0x06, 0x00}};
CAN_frame_t PYLON_4241 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4241,.data = {0x7E, 0x04, 0x62, 0x04, 0x11, 0x00, 0x03, 0x00}};
CAN_frame_t PYLON_4251 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4251,.data = {0x03, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4261 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4261,.data = {0xAC, 0xC7, 0x74, 0x27, 0x03, 0x00, 0x02, 0x00}};
CAN_frame_t PYLON_4271 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4271,.data = {0x7E, 0x04, 0x62, 0x04, 0x05, 0x00, 0x01, 0x00}};
CAN_frame_t PYLON_4281 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4281,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4291 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x4291,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4211 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4211,
.data = {0xA5, 0x09, 0x30, 0x75, 0x9D, 0x04, 0x2E, 0x64}};
CAN_frame_t PYLON_4221 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4221,
.data = {0x8C, 0x0A, 0xE9, 0x07, 0x4A, 0x79, 0x4A, 0x79}};
CAN_frame_t PYLON_4231 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4231,
.data = {0xDF, 0x0C, 0xDA, 0x0C, 0x03, 0x00, 0x06, 0x00}};
CAN_frame_t PYLON_4241 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4241,
.data = {0x7E, 0x04, 0x62, 0x04, 0x11, 0x00, 0x03, 0x00}};
CAN_frame_t PYLON_4251 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4251,
.data = {0x03, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4261 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4261,
.data = {0xAC, 0xC7, 0x74, 0x27, 0x03, 0x00, 0x02, 0x00}};
CAN_frame_t PYLON_4271 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4271,
.data = {0x7E, 0x04, 0x62, 0x04, 0x05, 0x00, 0x01, 0x00}};
CAN_frame_t PYLON_4281 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4281,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t PYLON_4291 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x4291,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
void update_values_can_pylon()
{ //This function maps all the values fetched from battery CAN to the correct CAN messages
void update_values_can_pylon() { //This function maps all the values fetched from battery CAN to the correct CAN messages
//There are more mappings that could be added, but this should be enough to use as a starting point
// Note we map both 0 and 1 messages
@ -62,12 +192,12 @@ void update_values_can_pylon()
PYLON_4211.data.u8[3] = (battery_current & 0x00FF);
//SOC (100.00%)
PYLON_4210.data.u8[6] = (SOC*0.01); //Remove decimals
PYLON_4211.data.u8[6] = (SOC*0.01); //Remove decimals
PYLON_4210.data.u8[6] = (SOC * 0.01); //Remove decimals
PYLON_4211.data.u8[6] = (SOC * 0.01); //Remove decimals
//StateOfHealth (100.00%)
PYLON_4210.data.u8[7] = (StateOfHealth*0.01);
PYLON_4211.data.u8[7] = (StateOfHealth*0.01);
PYLON_4210.data.u8[7] = (StateOfHealth * 0.01);
PYLON_4211.data.u8[7] = (StateOfHealth * 0.01);
//Minvoltage (eg 300.0V = 3000 , 16bits long) Charge Cutoff Voltage
PYLON_4220.data.u8[0] = (min_volt_pylon_can >> 8);
@ -82,8 +212,7 @@ void update_values_can_pylon()
PYLON_4221.data.u8[3] = (max_volt_pylon_can & 0x00FF);
//In case we run into any errors/faults, we can set charge / discharge forbidden
if(bms_status == FAULT)
{
if (bms_status == FAULT) {
PYLON_4280.data.u8[0] = 0xAA;
PYLON_4280.data.u8[1] = 0xAA;
PYLON_4280.data.u8[2] = 0xAA;
@ -93,43 +222,36 @@ void update_values_can_pylon()
PYLON_4281.data.u8[2] = 0xAA;
PYLON_4281.data.u8[3] = 0xAA;
}
}
void receive_can_pylon(CAN_frame_t rx_frame)
{
switch (rx_frame.MsgID)
{
case 0x4200: //Message originating from inverter. Depending on which data is required, act accordingly
if(rx_frame.data.u8[0] == 0x02)
{
send_setup_info();
}
if(rx_frame.data.u8[0] == 0x00)
{
send_system_data();
}
break;
void receive_can_pylon(CAN_frame_t rx_frame) {
switch (rx_frame.MsgID) {
case 0x4200: //Message originating from inverter. Depending on which data is required, act accordingly
if (rx_frame.data.u8[0] == 0x02) {
send_setup_info();
}
if (rx_frame.data.u8[0] == 0x00) {
send_system_data();
}
break;
default:
break;
break;
}
}
void send_setup_info()
{ //Ensemble information
#ifdef SEND_0
void send_setup_info() { //Ensemble information
#ifdef SEND_0
ESP32Can.CANWriteFrame(&PYLON_7310);
ESP32Can.CANWriteFrame(&PYLON_7320);
#endif
#ifdef SEND_1
#endif
#ifdef SEND_1
ESP32Can.CANWriteFrame(&PYLON_7311);
ESP32Can.CANWriteFrame(&PYLON_7321);
#endif
#endif
}
void send_system_data()
{ //System equipment information
#ifdef SEND_0
void send_system_data() { //System equipment information
#ifdef SEND_0
ESP32Can.CANWriteFrame(&PYLON_4210);
ESP32Can.CANWriteFrame(&PYLON_4220);
ESP32Can.CANWriteFrame(&PYLON_4230);
@ -139,8 +261,8 @@ void send_system_data()
ESP32Can.CANWriteFrame(&PYLON_4270);
ESP32Can.CANWriteFrame(&PYLON_4280);
ESP32Can.CANWriteFrame(&PYLON_4290);
#endif
#ifdef SEND_1
#endif
#ifdef SEND_1
ESP32Can.CANWriteFrame(&PYLON_4211);
ESP32Can.CANWriteFrame(&PYLON_4221);
ESP32Can.CANWriteFrame(&PYLON_4231);
@ -150,5 +272,5 @@ void send_system_data()
ESP32Can.CANWriteFrame(&PYLON_4271);
ESP32Can.CANWriteFrame(&PYLON_4281);
ESP32Can.CANWriteFrame(&PYLON_4291);
#endif
}
#endif
}

View file

@ -1,8 +1,8 @@
#ifndef PYLON_CAN_H
#define PYLON_CAN_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
extern uint16_t SOC;
extern uint16_t StateOfHealth;
@ -33,4 +33,4 @@ void receive_can_pylon(CAN_frame_t rx_frame);
void send_system_data();
void send_setup_info();
#endif
#endif

View file

@ -5,71 +5,147 @@
//TODO, change CAN sending routine once confirmed that 500ms interval is OK for this battery type
/* Do not change code below unless you are sure what you are doing */
static unsigned long previousMillis1s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis2s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis3s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis4s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis5s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis6s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis7s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis8s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis9s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis10s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis11s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis12s = 0; // will store last time a Xs CAN Message was send
static const int interval1s = 100; // interval (ms) at which send CAN Messages
static const int interval2s = 102; // interval (ms) at which send CAN Messages
static const int interval3s = 104; // interval (ms) at which send CAN Messages
static const int interval4s = 106; // interval (ms) at which send CAN Messages
static const int interval5s = 108; // interval (ms) at which send CAN Messages
static const int interval6s = 110; // interval (ms) at which send CAN Messages
static const int interval7s = 112; // interval (ms) at which send CAN Messages
static const int interval8s = 114; // interval (ms) at which send CAN Messages
static const int interval9s = 116; // interval (ms) at which send CAN Messages
static const int interval10s = 118; // interval (ms) at which send CAN Messages
static const int interval11s = 120; // interval (ms) at which send CAN Messages
static const int interval12s = 122; // interval (ms) at which send CAN Messages
static unsigned long previousMillis1s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis2s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis3s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis4s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis5s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis6s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis7s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis8s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis9s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis10s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis11s = 0; // will store last time a Xs CAN Message was send
static unsigned long previousMillis12s = 0; // will store last time a Xs CAN Message was send
static const int interval1s = 100; // interval (ms) at which send CAN Messages
static const int interval2s = 102; // interval (ms) at which send CAN Messages
static const int interval3s = 104; // interval (ms) at which send CAN Messages
static const int interval4s = 106; // interval (ms) at which send CAN Messages
static const int interval5s = 108; // interval (ms) at which send CAN Messages
static const int interval6s = 110; // interval (ms) at which send CAN Messages
static const int interval7s = 112; // interval (ms) at which send CAN Messages
static const int interval8s = 114; // interval (ms) at which send CAN Messages
static const int interval9s = 116; // interval (ms) at which send CAN Messages
static const int interval10s = 118; // interval (ms) at which send CAN Messages
static const int interval11s = 120; // interval (ms) at which send CAN Messages
static const int interval12s = 122; // interval (ms) at which send CAN Messages
//Actual content messages
static const CAN_frame_t SMA_558 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x558,.data = {0x03, 0x12, 0x00, 0x04, 0x00, 0x59, 0x07, 0x07}}; //7x BYD modules, Vendor ID 7 BYD
static const CAN_frame_t SMA_598 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x598,.data = {0x00, 0x00, 0x12, 0x34, 0x5A, 0xDE, 0x07, 0x4F}}; //B0-4 Serial, rest unknown
static const CAN_frame_t SMA_5D8 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x5D8,.data = {0x00, 0x42, 0x59, 0x44, 0x00, 0x00, 0x00, 0x00}}; //B Y D
static const CAN_frame_t SMA_618_1 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x618,.data = {0x00, 0x42, 0x61, 0x74, 0x74, 0x65, 0x72, 0x79}}; //0 B A T T E R Y
static const CAN_frame_t SMA_618_2 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x618,.data = {0x01, 0x2D, 0x42, 0x6F, 0x78, 0x20, 0x48, 0x39}}; //1 - B O X H
static const CAN_frame_t SMA_618_3 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x618,.data = {0x02, 0x2E, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00}}; //2 - 0
CAN_frame_t SMA_358 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x358,.data = {0x0F, 0x6C, 0x06, 0x20, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SMA_3D8 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x3D8,.data = {0x04, 0x10, 0x27, 0x10, 0x00, 0x18, 0xF9, 0x00}};
CAN_frame_t SMA_458 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x458,.data = {0x00, 0x00, 0x06, 0x75, 0x00, 0x00, 0x05, 0xD6}};
CAN_frame_t SMA_518 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x518,.data = {0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF}};
CAN_frame_t SMA_4D8 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x4D8,.data = {0x09, 0xFD, 0x00, 0x00, 0x00, 0xA8, 0x02, 0x08}};
CAN_frame_t SMA_158 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x158,.data = {0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0x6A, 0xAA, 0xAA}};
static const CAN_frame_t SMA_558 = {
.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x558,
.data = {0x03, 0x12, 0x00, 0x04, 0x00, 0x59, 0x07, 0x07}}; //7x BYD modules, Vendor ID 7 BYD
static const CAN_frame_t SMA_598 = {
.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x598,
.data = {0x00, 0x00, 0x12, 0x34, 0x5A, 0xDE, 0x07, 0x4F}}; //B0-4 Serial, rest unknown
static const CAN_frame_t SMA_5D8 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x5D8,
.data = {0x00, 0x42, 0x59, 0x44, 0x00, 0x00, 0x00, 0x00}}; //B Y D
static const CAN_frame_t SMA_618_1 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x618,
.data = {0x00, 0x42, 0x61, 0x74, 0x74, 0x65, 0x72, 0x79}}; //0 B A T T E R Y
static const CAN_frame_t SMA_618_2 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x618,
.data = {0x01, 0x2D, 0x42, 0x6F, 0x78, 0x20, 0x48, 0x39}}; //1 - B O X H
static const CAN_frame_t SMA_618_3 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x618,
.data = {0x02, 0x2E, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00}}; //2 - 0
CAN_frame_t SMA_358 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x358,
.data = {0x0F, 0x6C, 0x06, 0x20, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SMA_3D8 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x3D8,
.data = {0x04, 0x10, 0x27, 0x10, 0x00, 0x18, 0xF9, 0x00}};
CAN_frame_t SMA_458 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x458,
.data = {0x00, 0x00, 0x06, 0x75, 0x00, 0x00, 0x05, 0xD6}};
CAN_frame_t SMA_518 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x518,
.data = {0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF}};
CAN_frame_t SMA_4D8 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x4D8,
.data = {0x09, 0xFD, 0x00, 0x00, 0x00, 0xA8, 0x02, 0x08}};
CAN_frame_t SMA_158 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_std,
}},
.MsgID = 0x158,
.data = {0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0x6A, 0xAA, 0xAA}};
static int discharge_current = 0;
static int charge_current = 0;
static int temperature_average = 0;
static int ampere_hours_remaining = 0;
void update_values_can_sma()
{ //This function maps all the values fetched from battery CAN to the correct CAN messages
void update_values_can_sma() { //This function maps all the values fetched from battery CAN to the correct CAN messages
//Calculate values
charge_current = ((max_target_charge_power*10)/max_volt_sma_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
charge_current = ((max_target_charge_power * 10) /
max_volt_sma_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
//The above calculation results in (30 000*10)/3700=81A
charge_current = (charge_current*10); //Value needs a decimal before getting sent to inverter (81.0A)
charge_current = (charge_current * 10); //Value needs a decimal before getting sent to inverter (81.0A)
discharge_current = ((max_target_discharge_power*10)/max_volt_sma_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
discharge_current = ((max_target_discharge_power * 10) /
max_volt_sma_can); //Charge power in W , max volt in V+1decimal (P=UI, solve for I)
//The above calculation results in (30 000*10)/3700=81A
discharge_current = (discharge_current*10); //Value needs a decimal before getting sent to inverter (81.0A)
discharge_current = (discharge_current * 10); //Value needs a decimal before getting sent to inverter (81.0A)
temperature_average = ((temperature_max + temperature_min)/2);
temperature_average = ((temperature_max + temperature_min) / 2);
ampere_hours_remaining =
((remaining_capacity_Wh / battery_voltage) * 100); //(WH[10000] * V+1[3600])*100 = 270 (27.0Ah)
ampere_hours_remaining = ((remaining_capacity_Wh/battery_voltage)*100); //(WH[10000] * V+1[3600])*100 = 270 (27.0Ah)
//Map values to CAN messages
//Maxvoltage (eg 400.0V = 4000 , 16bits long)
SMA_358.data.u8[0] = (max_volt_sma_can >> 8);
SMA_358.data.u8[1] = (max_volt_sma_can & 0x00FF);
//Minvoltage (eg 300.0V = 3000 , 16bits long)
SMA_358.data.u8[2] = (min_volt_sma_can >> 8); //Minvoltage behaves strange on SMA, cuts out at 56% of the set value?
//Minvoltage (eg 300.0V = 3000 , 16bits long)
SMA_358.data.u8[2] = (min_volt_sma_can >> 8); //Minvoltage behaves strange on SMA, cuts out at 56% of the set value?
SMA_358.data.u8[3] = (min_volt_sma_can & 0x00FF);
//Discharge limited current, 500 = 50A, (0.1, A)
SMA_358.data.u8[4] = (discharge_current >> 8);
@ -103,97 +179,81 @@ void update_values_can_sma()
//TODO, add all error bits
}
void receive_can_sma(CAN_frame_t rx_frame)
{
switch (rx_frame.MsgID)
{
case 0x660: //Message originating from SMA inverter
void receive_can_sma(CAN_frame_t rx_frame) {
switch (rx_frame.MsgID) {
case 0x660: //Message originating from SMA inverter
break;
case 0x5E0: //Message originating from SMA inverter
case 0x5E0: //Message originating from SMA inverter
break;
case 0x560: //Message originating from SMA inverter
case 0x560: //Message originating from SMA inverter
break;
default:
break;
}
}
void send_can_sma()
{
void send_can_sma() {
unsigned long currentMillis = millis();
// Send CAN Message every X ms, 1000 for testing
if (currentMillis - previousMillis1s >= interval1s)
{
previousMillis1s = currentMillis;
// Send CAN Message every X ms, 1000 for testing
if (currentMillis - previousMillis1s >= interval1s) {
previousMillis1s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_558);
}
if (currentMillis - previousMillis2s >= interval2s)
{
previousMillis2s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_558);
}
if (currentMillis - previousMillis2s >= interval2s) {
previousMillis2s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_598);
}
if (currentMillis - previousMillis3s >= interval3s)
{
previousMillis3s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_598);
}
if (currentMillis - previousMillis3s >= interval3s) {
previousMillis3s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_5D8);
}
if (currentMillis - previousMillis4s >= interval4s)
{
previousMillis4s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_5D8);
}
if (currentMillis - previousMillis4s >= interval4s) {
previousMillis4s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_618_1);
}
if (currentMillis - previousMillis5s >= interval5s)
{
previousMillis5s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_618_1);
}
if (currentMillis - previousMillis5s >= interval5s) {
previousMillis5s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_618_2);
}
if (currentMillis - previousMillis6s >= interval6s)
{
previousMillis6s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_618_2);
}
if (currentMillis - previousMillis6s >= interval6s) {
previousMillis6s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_618_3);
}
if (currentMillis - previousMillis7s >= interval7s)
{
previousMillis7s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_618_3);
}
if (currentMillis - previousMillis7s >= interval7s) {
previousMillis7s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_358);
}
if (currentMillis - previousMillis8s >= interval8s)
{
previousMillis8s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_358);
}
if (currentMillis - previousMillis8s >= interval8s) {
previousMillis8s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_3D8);
}
if (currentMillis - previousMillis9s >= interval9s)
{
previousMillis9s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_3D8);
}
if (currentMillis - previousMillis9s >= interval9s) {
previousMillis9s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_458);
}
if (currentMillis - previousMillis10s >= interval10s)
{
previousMillis10s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_458);
}
if (currentMillis - previousMillis10s >= interval10s) {
previousMillis10s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_518);
}
if (currentMillis - previousMillis11s >= interval11s)
{
previousMillis11s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_518);
}
if (currentMillis - previousMillis11s >= interval11s) {
previousMillis11s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_4D8);
}
if (currentMillis - previousMillis12s >= interval12s)
{
previousMillis12s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_4D8);
}
if (currentMillis - previousMillis12s >= interval12s) {
previousMillis12s = currentMillis;
ESP32Can.CANWriteFrame(&SMA_158);
}
}
ESP32Can.CANWriteFrame(&SMA_158);
}
}

View file

@ -1,27 +1,27 @@
#ifndef SMA_CAN_H
#define SMA_CAN_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
extern uint16_t SOC; //SOC%, 0-100.00 (0-10000)
extern uint16_t StateOfHealth; //SOH%, 0-100.00 (0-10000)
extern uint16_t battery_voltage; //V+1, 0-500.0 (0-5000)
extern uint16_t battery_current; //A+1, Goes thru convert2unsignedint16 function (5.0A = 50, -5.0A = 65485)
extern uint16_t capacity_Wh; //Wh, 0-60000
extern uint16_t remaining_capacity_Wh; //Wh, 0-60000
extern uint16_t max_target_discharge_power; //W, 0-60000
extern uint16_t max_target_charge_power; //W, 0-60000
extern uint16_t bms_status; //Enum, 0-5
extern uint16_t bms_char_dis_status; //Enum, 0-2
extern uint16_t stat_batt_power; //W, Goes thru convert2unsignedint16 function (5W = 5, -5W = 65530)
extern uint16_t temperature_min; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t temperature_max; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t cell_max_voltage; //mV, 0-4350
extern uint16_t cell_min_voltage; //mV, 0-4350
extern uint16_t SOC; //SOC%, 0-100.00 (0-10000)
extern uint16_t StateOfHealth; //SOH%, 0-100.00 (0-10000)
extern uint16_t battery_voltage; //V+1, 0-500.0 (0-5000)
extern uint16_t battery_current; //A+1, Goes thru convert2unsignedint16 function (5.0A = 50, -5.0A = 65485)
extern uint16_t capacity_Wh; //Wh, 0-60000
extern uint16_t remaining_capacity_Wh; //Wh, 0-60000
extern uint16_t max_target_discharge_power; //W, 0-60000
extern uint16_t max_target_charge_power; //W, 0-60000
extern uint16_t bms_status; //Enum, 0-5
extern uint16_t bms_char_dis_status; //Enum, 0-2
extern uint16_t stat_batt_power; //W, Goes thru convert2unsignedint16 function (5W = 5, -5W = 65530)
extern uint16_t temperature_min; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t temperature_max; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t cell_max_voltage; //mV, 0-4350
extern uint16_t cell_min_voltage; //mV, 0-4350
extern uint16_t min_volt_sma_can;
extern uint16_t max_volt_sma_can;
extern uint8_t LEDcolor; //Enum, 0-2
extern uint8_t LEDcolor; //Enum, 0-2
// Definitions for BMS status
#define STANDBY 0
#define INACTIVE 1
@ -34,4 +34,4 @@ void update_values_can_sma();
void send_can_sma();
void receive_can_sma(CAN_frame_t rx_frame);
#endif
#endif

View file

@ -5,53 +5,280 @@
/* This implementation of the SOFAR can protocol is halfway done. What's missing is implementing the inverter replies, all the CAN messages are listed, but the can sending is missing. */
/* Do not change code below unless you are sure what you are doing */
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
static const int interval100 = 100; // interval (ms) at which send CAN Messages
static unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
static const int interval100 = 100; // interval (ms) at which send CAN Messages
//Actual content messages
//Note that these are technically extended frames. If more batteries are put in parallel,the first battery sends 0x351 the next battery sends 0x1351 etc. 16 batteries in parallel supported
CAN_frame_t SOFAR_351 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x351,.data = {0xC6, 0x08, 0xFA, 0x00, 0xFA, 0x00, 0x80, 0x07}};
CAN_frame_t SOFAR_355 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x355,.data = {0x31, 0x00, 0x64, 0x00, 0xFF, 0xFF, 0xF6, 0x00}};
CAN_frame_t SOFAR_356 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x356,.data = {0x36, 0x08, 0x10, 0x00, 0xD0, 0x00, 0x01, 0x00}};
CAN_frame_t SOFAR_30F = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x30F,.data = {0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_359 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x359,.data = {0x00, 0x00, 0x00, 0x00, 0x04, 0x10, 0x27, 0x10}};
CAN_frame_t SOFAR_35E = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x35E,.data = {0x41, 0x4D, 0x41, 0x53, 0x53, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_35F = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x35F,.data = {0x00, 0x00, 0x24, 0x4E, 0x32, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_35A = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x35A,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_351 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x351,
.data = {0xC6, 0x08, 0xFA, 0x00, 0xFA, 0x00, 0x80, 0x07}};
CAN_frame_t SOFAR_355 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x355,
.data = {0x31, 0x00, 0x64, 0x00, 0xFF, 0xFF, 0xF6, 0x00}};
CAN_frame_t SOFAR_356 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x356,
.data = {0x36, 0x08, 0x10, 0x00, 0xD0, 0x00, 0x01, 0x00}};
CAN_frame_t SOFAR_30F = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x30F,
.data = {0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_359 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x359,
.data = {0x00, 0x00, 0x00, 0x00, 0x04, 0x10, 0x27, 0x10}};
CAN_frame_t SOFAR_35E = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x35E,
.data = {0x41, 0x4D, 0x41, 0x53, 0x53, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_35F = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x35F,
.data = {0x00, 0x00, 0x24, 0x4E, 0x32, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_35A = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x35A,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_670 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x670,.data = {0x00, 0x8A, 0x33, 0x11, 0x59, 0x1A, 0x00, 0x00}};
CAN_frame_t SOFAR_671 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x671,.data = {0x00, 0x42, 0x48, 0x55, 0x35, 0x31, 0x32, 0x30}};
CAN_frame_t SOFAR_672 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x672,.data = {0x00, 0x32, 0x35, 0x45, 0x50, 0x43, 0x32, 0x31}};
CAN_frame_t SOFAR_673 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x673,.data = {0x00, 0x34, 0x32, 0x36, 0x31, 0x36, 0x32, 0x00}};
CAN_frame_t SOFAR_680 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x680,.data = {0x00, 0xB7, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_681 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x681,.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_682 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x682,.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_683 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x683,.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_684 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x684,.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_685 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x685,.data = {0x00, 0xB3, 0x0C, 0xBB, 0x0C, 0xB3, 0x0C, 0x00}};
CAN_frame_t SOFAR_690 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x690,.data = {0x00, 0xD7, 0x00, 0xD4, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_691 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x691,.data = {0x00, 0xD4, 0x00, 0xD1, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_6A0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x6A0,.data = {0x00, 0xFA, 0x00, 0xDD, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_6B0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x6B0,.data = {0x00, 0xF6, 0x00, 0x06, 0x02, 0x01, 0x00, 0x00}};
CAN_frame_t SOFAR_6C0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x6C0,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_770 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x770,.data = {0x00, 0x56, 0x0B, 0xF0, 0x58, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_771 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x771,.data = {0x00, 0x42, 0x48, 0x55, 0x35, 0x31, 0x32, 0x30}};
CAN_frame_t SOFAR_772 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x772,.data = {0x00, 0x32, 0x35, 0x45, 0x50, 0x43, 0x32, 0x31}};
CAN_frame_t SOFAR_773 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x773,.data = {0x00, 0x34, 0x32, 0x36, 0x31, 0x36, 0x32, 0x00}};
CAN_frame_t SOFAR_780 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x780,.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_781 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x781,.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_782 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x782,.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_783 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x783,.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_784 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x784,.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_785 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x785,.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_790 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x790,.data = {0x00, 0xCD, 0x00, 0xCF, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_791 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x791,.data = {0x00, 0xCD, 0x00, 0xCF, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_7A0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7A0,.data = {0x00, 0xFA, 0x00, 0xE1, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_7B0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7B0,.data = {0x00, 0xF9, 0x00, 0x06, 0x02, 0xE9, 0x5D, 0x00}};
CAN_frame_t SOFAR_7C0 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x7C0,.data = {0x00, 0x00, 0x00, 0x04, 0x00, 0x04, 0x80, 0x00}};
CAN_frame_t SOFAR_670 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x670,
.data = {0x00, 0x8A, 0x33, 0x11, 0x59, 0x1A, 0x00, 0x00}};
CAN_frame_t SOFAR_671 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x671,
.data = {0x00, 0x42, 0x48, 0x55, 0x35, 0x31, 0x32, 0x30}};
CAN_frame_t SOFAR_672 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x672,
.data = {0x00, 0x32, 0x35, 0x45, 0x50, 0x43, 0x32, 0x31}};
CAN_frame_t SOFAR_673 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x673,
.data = {0x00, 0x34, 0x32, 0x36, 0x31, 0x36, 0x32, 0x00}};
CAN_frame_t SOFAR_680 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x680,
.data = {0x00, 0xB7, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_681 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x681,
.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_682 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x682,
.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_683 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x683,
.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_684 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x684,
.data = {0x00, 0xB6, 0x0C, 0xB3, 0x0C, 0xB4, 0x0C, 0x00}};
CAN_frame_t SOFAR_685 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x685,
.data = {0x00, 0xB3, 0x0C, 0xBB, 0x0C, 0xB3, 0x0C, 0x00}};
CAN_frame_t SOFAR_690 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x690,
.data = {0x00, 0xD7, 0x00, 0xD4, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_691 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x691,
.data = {0x00, 0xD4, 0x00, 0xD1, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_6A0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x6A0,
.data = {0x00, 0xFA, 0x00, 0xDD, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_6B0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x6B0,
.data = {0x00, 0xF6, 0x00, 0x06, 0x02, 0x01, 0x00, 0x00}};
CAN_frame_t SOFAR_6C0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x6C0,
.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_770 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x770,
.data = {0x00, 0x56, 0x0B, 0xF0, 0x58, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_771 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x771,
.data = {0x00, 0x42, 0x48, 0x55, 0x35, 0x31, 0x32, 0x30}};
CAN_frame_t SOFAR_772 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x772,
.data = {0x00, 0x32, 0x35, 0x45, 0x50, 0x43, 0x32, 0x31}};
CAN_frame_t SOFAR_773 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x773,
.data = {0x00, 0x34, 0x32, 0x36, 0x31, 0x36, 0x32, 0x00}};
CAN_frame_t SOFAR_780 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x780,
.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_781 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x781,
.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_782 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x782,
.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_783 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x783,
.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_784 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x784,
.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_785 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x785,
.data = {0x00, 0xEB, 0x0C, 0xED, 0x0C, 0xED, 0x0C, 0x00}};
CAN_frame_t SOFAR_790 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x790,
.data = {0x00, 0xCD, 0x00, 0xCF, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_791 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x791,
.data = {0x00, 0xCD, 0x00, 0xCF, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_7A0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7A0,
.data = {0x00, 0xFA, 0x00, 0xE1, 0x00, 0x00, 0x00, 0x00}};
CAN_frame_t SOFAR_7B0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7B0,
.data = {0x00, 0xF9, 0x00, 0x06, 0x02, 0xE9, 0x5D, 0x00}};
CAN_frame_t SOFAR_7C0 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x7C0,
.data = {0x00, 0x00, 0x00, 0x04, 0x00, 0x04, 0x80, 0x00}};
void update_values_can_sofar()
{ //This function maps all the values fetched from battery CAN to the correct CAN messages
void update_values_can_sofar() { //This function maps all the values fetched from battery CAN to the correct CAN messages
//Maxvoltage (eg 400.0V = 4000 , 16bits long) Charge Cutoff Voltage
SOFAR_351.data.u8[0] = (max_volt_sofar_can >> 8);
@ -63,13 +290,13 @@ void update_values_can_sofar()
//Minvoltage (eg 300.0V = 3000 , 16bits long) Discharge Cutoff Voltage
SOFAR_351.data.u8[6] = (min_volt_sofar_can >> 8);
SOFAR_351.data.u8[7] = (min_volt_sofar_can & 0x00FF);
//SOC
SOFAR_355.data.u8[0] = (SOC/100);
SOFAR_355.data.u8[2] = (StateOfHealth/100);
SOFAR_355.data.u8[0] = (SOC / 100);
SOFAR_355.data.u8[2] = (StateOfHealth / 100);
//SOFAR_355.data.u8[6] = (AH_remaining >> 8);
//SOFAR_355.data.u8[7] = (AH_remaining & 0x00FF);
//Voltage (370.0)
SOFAR_356.data.u8[0] = (battery_voltage >> 8);
SOFAR_356.data.u8[1] = (battery_voltage & 0x00FF);
@ -77,41 +304,36 @@ void update_values_can_sofar()
SOFAR_356.data.u8[3] = (battery_current & 0x00FF);
SOFAR_356.data.u8[2] = (temperature_max >> 8);
SOFAR_356.data.u8[3] = (temperature_max & 0x00FF);
}
void receive_can_sofar(CAN_frame_t rx_frame)
{
switch (rx_frame.MsgID)
{ //In here we need to respond to the inverter. TODO make logic
void receive_can_sofar(CAN_frame_t rx_frame) {
switch (rx_frame.MsgID) { //In here we need to respond to the inverter. TODO make logic
case 0x605:
//frame1_605 = rx_frame.data.u8[1];
//frame3_605 = rx_frame.data.u8[3];
break;
break;
case 0x705:
//frame1_705 = rx_frame.data.u8[1];
//frame3_705 = rx_frame.data.u8[3];
break;
break;
default:
break;
break;
}
}
void send_can_sofar()
{
void send_can_sofar() {
unsigned long currentMillis = millis();
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100)
{
previousMillis100 = currentMillis;
//Frames actively reported by BMS
ESP32Can.CANWriteFrame(&SOFAR_351);
ESP32Can.CANWriteFrame(&SOFAR_355);
ESP32Can.CANWriteFrame(&SOFAR_356);
ESP32Can.CANWriteFrame(&SOFAR_30F);
ESP32Can.CANWriteFrame(&SOFAR_359);
ESP32Can.CANWriteFrame(&SOFAR_35E);
ESP32Can.CANWriteFrame(&SOFAR_35F);
ESP32Can.CANWriteFrame(&SOFAR_35A);
}
}
// Send 100ms CAN Message
if (currentMillis - previousMillis100 >= interval100) {
previousMillis100 = currentMillis;
//Frames actively reported by BMS
ESP32Can.CANWriteFrame(&SOFAR_351);
ESP32Can.CANWriteFrame(&SOFAR_355);
ESP32Can.CANWriteFrame(&SOFAR_356);
ESP32Can.CANWriteFrame(&SOFAR_30F);
ESP32Can.CANWriteFrame(&SOFAR_359);
ESP32Can.CANWriteFrame(&SOFAR_35E);
ESP32Can.CANWriteFrame(&SOFAR_35F);
ESP32Can.CANWriteFrame(&SOFAR_35A);
}
}

View file

@ -1,27 +1,27 @@
#ifndef SOFAR_CAN_H
#define SOFAR_CAN_H
#include <Arduino.h>
#include "../devboard/can/ESP32CAN.h"
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
// These parameters need to be mapped for the inverter
extern uint16_t SOC; //SOC%, 0-100.00 (0-10000)
extern uint16_t StateOfHealth; //SOH%, 0-100.00 (0-10000)
extern uint16_t battery_voltage; //V+1, 0-500.0 (0-5000)
extern uint16_t battery_current; //A+1, Goes thru convert2unsignedint16 function (5.0A = 50, -5.0A = 65485)
extern uint16_t capacity_Wh; //Wh, 0-60000
extern uint16_t remaining_capacity_Wh; //Wh, 0-60000
extern uint16_t max_target_discharge_power; //W, 0-60000
extern uint16_t max_target_charge_power; //W, 0-60000
extern uint16_t bms_status; //Enum, 0-5
extern uint16_t bms_char_dis_status; //Enum, 0-2
extern uint16_t stat_batt_power; //W, Goes thru convert2unsignedint16 function (5W = 5, -5W = 65530)
extern uint16_t temperature_min; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t temperature_max; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t cell_max_voltage; //mV, 0-4350
extern uint16_t cell_min_voltage; //mV, 0-4350
extern uint8_t batteryAllowsContactorClosing; //Bool, 1=true, 0=false
extern uint8_t LEDcolor; //Enum, 0-2
extern uint16_t SOC; //SOC%, 0-100.00 (0-10000)
extern uint16_t StateOfHealth; //SOH%, 0-100.00 (0-10000)
extern uint16_t battery_voltage; //V+1, 0-500.0 (0-5000)
extern uint16_t battery_current; //A+1, Goes thru convert2unsignedint16 function (5.0A = 50, -5.0A = 65485)
extern uint16_t capacity_Wh; //Wh, 0-60000
extern uint16_t remaining_capacity_Wh; //Wh, 0-60000
extern uint16_t max_target_discharge_power; //W, 0-60000
extern uint16_t max_target_charge_power; //W, 0-60000
extern uint16_t bms_status; //Enum, 0-5
extern uint16_t bms_char_dis_status; //Enum, 0-2
extern uint16_t stat_batt_power; //W, Goes thru convert2unsignedint16 function (5W = 5, -5W = 65530)
extern uint16_t temperature_min; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t temperature_max; //C+1, Goes thru convert2unsignedint16 function (15.0C = 150, -15.0C = 65385)
extern uint16_t cell_max_voltage; //mV, 0-4350
extern uint16_t cell_min_voltage; //mV, 0-4350
extern uint8_t batteryAllowsContactorClosing; //Bool, 1=true, 0=false
extern uint8_t LEDcolor; //Enum, 0-2
extern uint16_t min_volt_sofar_can;
extern uint16_t max_volt_sofar_can;
// Definitions for BMS status
@ -36,4 +36,4 @@ void update_values_can_sofar();
void send_can_sofar();
void receive_can_sofar(CAN_frame_t rx_frame);
#endif
#endif

View file

@ -8,161 +8,221 @@ static int STATE = BATTERY_ANNOUNCE;
static unsigned long LastFrameTime = 0;
static int number_of_batteries = 1;
//CAN message translations from this amazing repository: https://github.com/rand12345/solax_can_bus
//CAN message translations from this amazing repository: https://github.com/rand12345/solax_can_bus
CAN_frame_t SOLAX_1801 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1801,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}};
CAN_frame_t SOLAX_1872 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1872,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_Limits
CAN_frame_t SOLAX_1873 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1873,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_PackData
CAN_frame_t SOLAX_1874 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1874,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_CellData
CAN_frame_t SOLAX_1875 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1875,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_Status
CAN_frame_t SOLAX_1876 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1876,.data = {0x0, 0x0, 0xE2, 0x0C, 0x0, 0x0, 0xD7, 0x0C}}; //BMS_PackTemps
CAN_frame_t SOLAX_1877 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1877,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}};
CAN_frame_t SOLAX_1878 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1878,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_PackStats
CAN_frame_t SOLAX_1879 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1879,.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}};
CAN_frame_t SOLAX_1881 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1881,.data = {0x10, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; // E.g.: 0 6 S B M S F A
CAN_frame_t SOLAX_1882 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_ext,}},.MsgID = 0x1882,.data = {0x10, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; // E.g.: 0 2 3 A B 0 5 2
CAN_frame_t SOLAX_100A001 = {.FIR = {.B = {.DLC = 0,.FF = CAN_frame_ext,}},.MsgID = 0x100A001,.data = {}};
CAN_frame_t SOLAX_1801 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1801,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}};
CAN_frame_t SOLAX_1872 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1872,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_Limits
CAN_frame_t SOLAX_1873 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1873,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_PackData
CAN_frame_t SOLAX_1874 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1874,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_CellData
CAN_frame_t SOLAX_1875 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1875,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_Status
CAN_frame_t SOLAX_1876 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1876,
.data = {0x0, 0x0, 0xE2, 0x0C, 0x0, 0x0, 0xD7, 0x0C}}; //BMS_PackTemps
CAN_frame_t SOLAX_1877 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1877,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}};
CAN_frame_t SOLAX_1878 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1878,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; //BMS_PackStats
CAN_frame_t SOLAX_1879 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1879,
.data = {0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}};
CAN_frame_t SOLAX_1881 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1881,
.data = {0x10, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; // E.g.: 0 6 S B M S F A
CAN_frame_t SOLAX_1882 = {.FIR = {.B =
{
.DLC = 8,
.FF = CAN_frame_ext,
}},
.MsgID = 0x1882,
.data = {0x10, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}}; // E.g.: 0 2 3 A B 0 5 2
CAN_frame_t SOLAX_100A001 = {.FIR = {.B =
{
.DLC = 0,
.FF = CAN_frame_ext,
}},
.MsgID = 0x100A001,
.data = {}};
// __builtin_bswap64 needed to convert to ESP32 little endian format
// Byte[4] defines the requested contactor state: 1 = Closed , 0 = Open
#define Contactor_Open_Payload __builtin_bswap64(0x0200010000000000)
#define Contactor_Close_Payload __builtin_bswap64(0x0200010001000000)
#define Contactor_Open_Payload __builtin_bswap64(0x0200010000000000)
#define Contactor_Close_Payload __builtin_bswap64(0x0200010001000000)
void CAN_WriteFrame(CAN_frame_t* tx_frame)
{
#ifdef DUAL_CAN
CANMessage MCP2515Frame; //Struct with ACAN2515 library format, needed to use the MCP2515 library
void CAN_WriteFrame(CAN_frame_t* tx_frame) {
#ifdef DUAL_CAN
CANMessage MCP2515Frame; //Struct with ACAN2515 library format, needed to use the MCP2515 library
MCP2515Frame.id = tx_frame->MsgID;
MCP2515Frame.ext = tx_frame->FIR.B.FF;
MCP2515Frame.len = tx_frame->FIR.B.DLC;
for (uint8_t i=0 ; i<MCP2515Frame.len ; i++) {
MCP2515Frame.data[i] = tx_frame->data.u8[i];
}
for (uint8_t i = 0; i < MCP2515Frame.len; i++) {
MCP2515Frame.data[i] = tx_frame->data.u8[i];
}
can.tryToSend(MCP2515Frame);
#else
#else
ESP32Can.CANWriteFrame(tx_frame);
#endif
#endif
}
void update_values_can_solax()
{ //This function maps all the values fetched from battery CAN to the correct CAN messages
void update_values_can_solax() { //This function maps all the values fetched from battery CAN to the correct CAN messages
// If not receiveing any communication from the inverter, open contactors and return to battery announce state
if (millis() - LastFrameTime >= SolaxTimeout)
{
if (millis() - LastFrameTime >= SolaxTimeout) {
inverterAllowsContactorClosing = 0;
STATE = BATTERY_ANNOUNCE;
}
//Calculate the required values
temperature_average = ((temperature_max + temperature_min)/2);
temperature_average = ((temperature_max + temperature_min) / 2);
//max_target_charge_power (30000W max)
if(SOC > 9999) //99.99%
{ //Additional safety incase SOC% is 100, then do not charge battery further
if (SOC > 9999) //99.99%
{ //Additional safety incase SOC% is 100, then do not charge battery further
max_charge_rate_amp = 0;
}
else
{ //We can pass on the battery charge rate (in W) to the inverter (that takes A)
if(max_target_charge_power >= 30000)
{
max_charge_rate_amp = 75; //Incase battery can take over 30kW, cap value to 75A
}
else
{ //Calculate the W value into A
max_charge_rate_amp = (max_target_charge_power/(battery_voltage*0.1)); // P/U = I
} else { //We can pass on the battery charge rate (in W) to the inverter (that takes A)
if (max_target_charge_power >= 30000) {
max_charge_rate_amp = 75; //Incase battery can take over 30kW, cap value to 75A
} else { //Calculate the W value into A
max_charge_rate_amp = (max_target_charge_power / (battery_voltage * 0.1)); // P/U = I
}
}
//max_target_discharge_power (30000W max)
if(SOC < 100) //1.00%
{ //Additional safety incase SOC% is below 1, then do not charge battery further
if (SOC < 100) //1.00%
{ //Additional safety incase SOC% is below 1, then do not charge battery further
max_discharge_rate_amp = 0;
}
else
{ //We can pass on the battery discharge rate to the inverter
if(max_target_discharge_power >= 30000)
{
max_discharge_rate_amp = 75; //Incase battery can be charged with over 30kW, cap value to 75A
}
else
{ //Calculate the W value into A
max_discharge_rate_amp = (max_target_discharge_power/(battery_voltage*0.1)); // P/U = I
} else { //We can pass on the battery discharge rate to the inverter
if (max_target_discharge_power >= 30000) {
max_discharge_rate_amp = 75; //Incase battery can be charged with over 30kW, cap value to 75A
} else { //Calculate the W value into A
max_discharge_rate_amp = (max_target_discharge_power / (battery_voltage * 0.1)); // P/U = I
}
}
//Put the values into the CAN messages
//BMS_Limits
SOLAX_1872.data.u8[0] = (uint8_t) max_volt_solax_can; //Todo, scaling OK?
SOLAX_1872.data.u8[0] = (uint8_t)max_volt_solax_can; //Todo, scaling OK?
SOLAX_1872.data.u8[1] = (max_volt_solax_can >> 8);
SOLAX_1872.data.u8[2] = (uint8_t) min_volt_solax_can; //Todo, scaling OK?
SOLAX_1872.data.u8[2] = (uint8_t)min_volt_solax_can; //Todo, scaling OK?
SOLAX_1872.data.u8[3] = (min_volt_solax_can >> 8);
SOLAX_1872.data.u8[4] = (uint8_t) (max_charge_rate_amp*10); //Todo, scaling OK?
SOLAX_1872.data.u8[5] = ((max_charge_rate_amp*10) >> 8);
SOLAX_1872.data.u8[6] = (uint8_t) (max_discharge_rate_amp*10); //Todo, scaling OK?
SOLAX_1872.data.u8[7] = ((max_discharge_rate_amp*10) >> 8);
SOLAX_1872.data.u8[4] = (uint8_t)(max_charge_rate_amp * 10); //Todo, scaling OK?
SOLAX_1872.data.u8[5] = ((max_charge_rate_amp * 10) >> 8);
SOLAX_1872.data.u8[6] = (uint8_t)(max_discharge_rate_amp * 10); //Todo, scaling OK?
SOLAX_1872.data.u8[7] = ((max_discharge_rate_amp * 10) >> 8);
//BMS_PackData
SOLAX_1873.data.u8[0] = (uint8_t) battery_voltage; // OK
SOLAX_1873.data.u8[0] = (uint8_t)battery_voltage; // OK
SOLAX_1873.data.u8[1] = (battery_voltage >> 8);
SOLAX_1873.data.u8[2] = (int8_t) battery_current; // OK, Signed (Active current in Amps x 10)
SOLAX_1873.data.u8[2] = (int8_t)battery_current; // OK, Signed (Active current in Amps x 10)
SOLAX_1873.data.u8[3] = (battery_current >> 8);
SOLAX_1873.data.u8[4] = (uint8_t) (SOC/100); //SOC (100.00%)
SOLAX_1873.data.u8[4] = (uint8_t)(SOC / 100); //SOC (100.00%)
//SOLAX_1873.data.u8[5] = //Seems like this is not required? Or shall we put SOC decimals here?
SOLAX_1873.data.u8[6] = (uint8_t) (remaining_capacity_Wh/100); //Todo, scaling OK?
SOLAX_1873.data.u8[7] = ((remaining_capacity_Wh/100) >> 8);
SOLAX_1873.data.u8[6] = (uint8_t)(remaining_capacity_Wh / 100); //Todo, scaling OK?
SOLAX_1873.data.u8[7] = ((remaining_capacity_Wh / 100) >> 8);
//BMS_CellData
SOLAX_1874.data.u8[0] = (uint8_t) temperature_max;
SOLAX_1874.data.u8[0] = (uint8_t)temperature_max;
SOLAX_1874.data.u8[1] = (temperature_max >> 8);
SOLAX_1874.data.u8[2] = (uint8_t) temperature_min;
SOLAX_1874.data.u8[2] = (uint8_t)temperature_min;
SOLAX_1874.data.u8[3] = (temperature_min >> 8);
SOLAX_1874.data.u8[4] = (uint8_t) (cell_max_voltage); //Todo, scaling OK? Supposed to be alarm trigger absolute cell max?
SOLAX_1874.data.u8[5] = (cell_max_voltage >> 8);
SOLAX_1874.data.u8[6] = (uint8_t) (cell_min_voltage); //Todo, scaling OK? Supposed to be alarm trigger absolute cell min?
SOLAX_1874.data.u8[4] =
(uint8_t)(cell_max_voltage); //Todo, scaling OK? Supposed to be alarm trigger absolute cell max?
SOLAX_1874.data.u8[5] = (cell_max_voltage >> 8);
SOLAX_1874.data.u8[6] =
(uint8_t)(cell_min_voltage); //Todo, scaling OK? Supposed to be alarm trigger absolute cell min?
SOLAX_1874.data.u8[7] = (cell_min_voltage >> 8);
//BMS_Status
SOLAX_1875.data.u8[0] = (uint8_t) temperature_average;
SOLAX_1875.data.u8[0] = (uint8_t)temperature_average;
SOLAX_1875.data.u8[1] = (temperature_average >> 8);
SOLAX_1875.data.u8[2] = (uint8_t) 0; // Number of slave batteries
SOLAX_1875.data.u8[4] = (uint8_t) 0; // Contactor Status 0=off, 1=on.
SOLAX_1875.data.u8[2] = (uint8_t)0; // Number of slave batteries
SOLAX_1875.data.u8[4] = (uint8_t)0; // Contactor Status 0=off, 1=on.
//BMS_PackTemps (strange name, since it has voltages?)
SOLAX_1876.data.u8[2] = (uint8_t) cell_max_voltage; //Todo, scaling OK?
SOLAX_1876.data.u8[2] = (uint8_t)cell_max_voltage; //Todo, scaling OK?
SOLAX_1876.data.u8[3] = (cell_min_voltage >> 8);
SOLAX_1876.data.u8[6] = (uint8_t) cell_min_voltage; //Todo, scaling OK?
SOLAX_1876.data.u8[6] = (uint8_t)cell_min_voltage; //Todo, scaling OK?
SOLAX_1876.data.u8[7] = (cell_min_voltage >> 8);
//Unknown
SOLAX_1877.data.u8[4] = (uint8_t) 0x50; // Battery type
SOLAX_1877.data.u8[6] = (uint8_t) 0x22; // Firmware version?
SOLAX_1877.data.u8[7] = (uint8_t) 0x02; // The above firmware version applies to:02 = Master BMS, 10 = S1, 20 = S2, 30 = S3, 40 = S4
SOLAX_1877.data.u8[4] = (uint8_t)0x50; // Battery type
SOLAX_1877.data.u8[6] = (uint8_t)0x22; // Firmware version?
SOLAX_1877.data.u8[7] =
(uint8_t)0x02; // The above firmware version applies to:02 = Master BMS, 10 = S1, 20 = S2, 30 = S3, 40 = S4
//BMS_PackStats
SOLAX_1878.data.u8[0] = (uint8_t) (battery_voltage); //TODO, should this be max or current voltage?
SOLAX_1878.data.u8[0] = (uint8_t)(battery_voltage); //TODO, should this be max or current voltage?
SOLAX_1878.data.u8[1] = ((battery_voltage) >> 8);
SOLAX_1878.data.u8[4] = (uint8_t) capacity_Wh; //TODO, scaling OK?
SOLAX_1878.data.u8[4] = (uint8_t)capacity_Wh; //TODO, scaling OK?
SOLAX_1878.data.u8[5] = (capacity_Wh >> 8);
// BMS_Answer
SOLAX_1801.data.u8[0] = 2;
SOLAX_1801.data.u8[2] = 1;
SOLAX_1801.data.u8[4] = 1;
}
void receive_can_solax(CAN_frame_t rx_frame)
{
if (rx_frame.MsgID == 0x1871 && rx_frame.data.u8[0] == (0x01) || rx_frame.MsgID == 0x1871 && rx_frame.data.u8[0] == (0x02)) {
void receive_can_solax(CAN_frame_t rx_frame) {
if (rx_frame.MsgID == 0x1871 && rx_frame.data.u8[0] == (0x01) ||
rx_frame.MsgID == 0x1871 && rx_frame.data.u8[0] == (0x02)) {
LastFrameTime = millis();
switch(STATE)
{
case(BATTERY_ANNOUNCE):
switch (STATE) {
case (BATTERY_ANNOUNCE):
Serial.println("Solax Battery State: Announce");
inverterAllowsContactorClosing = 0;
SOLAX_1875.data.u8[4] = (0x00); // Inform Inverter: Contactor 0=off, 1=on.
for (int i=0; i <= number_of_batteries; i++) {
SOLAX_1875.data.u8[4] = (0x00); // Inform Inverter: Contactor 0=off, 1=on.
for (int i = 0; i <= number_of_batteries; i++) {
CAN_WriteFrame(&SOLAX_1872);
CAN_WriteFrame(&SOLAX_1873);
CAN_WriteFrame(&SOLAX_1874);
@ -171,15 +231,15 @@ void receive_can_solax(CAN_frame_t rx_frame)
CAN_WriteFrame(&SOLAX_1877);
CAN_WriteFrame(&SOLAX_1878);
}
CAN_WriteFrame(&SOLAX_100A001); //BMS Announce
CAN_WriteFrame(&SOLAX_100A001); //BMS Announce
// Message from the inverter to proceed to contactor closing
// Byte 4 changes from 0 to 1
if (rx_frame.data.u64 == Contactor_Close_Payload)
STATE = WAITING_FOR_CONTACTOR;
break;
STATE = WAITING_FOR_CONTACTOR;
break;
case(WAITING_FOR_CONTACTOR):
SOLAX_1875.data.u8[4] = (0x00); // Inform Inverter: Contactor 0=off, 1=on.
case (WAITING_FOR_CONTACTOR):
SOLAX_1875.data.u8[4] = (0x00); // Inform Inverter: Contactor 0=off, 1=on.
CAN_WriteFrame(&SOLAX_1872);
CAN_WriteFrame(&SOLAX_1873);
CAN_WriteFrame(&SOLAX_1874);
@ -187,14 +247,14 @@ void receive_can_solax(CAN_frame_t rx_frame)
CAN_WriteFrame(&SOLAX_1876);
CAN_WriteFrame(&SOLAX_1877);
CAN_WriteFrame(&SOLAX_1878);
CAN_WriteFrame(&SOLAX_1801); // Announce that the battery will be connected
STATE = CONTACTOR_CLOSED; // Jump to Contactor Closed State
CAN_WriteFrame(&SOLAX_1801); // Announce that the battery will be connected
STATE = CONTACTOR_CLOSED; // Jump to Contactor Closed State
Serial.println("Solax Battery State: Contactor Closed");
break;
case(CONTACTOR_CLOSED):
break;
case (CONTACTOR_CLOSED):
inverterAllowsContactorClosing = 1;
SOLAX_1875.data.u8[4] = (0x01); // Inform Inverter: Contactor 0=off, 1=on.
SOLAX_1875.data.u8[4] = (0x01); // Inform Inverter: Contactor 0=off, 1=on.
CAN_WriteFrame(&SOLAX_1872);
CAN_WriteFrame(&SOLAX_1873);
CAN_WriteFrame(&SOLAX_1874);
@ -205,18 +265,17 @@ void receive_can_solax(CAN_frame_t rx_frame)
// Message from the inverter to open contactor
// Byte 4 changes from 1 to 0
if (rx_frame.data.u64 == Contactor_Open_Payload)
STATE = BATTERY_ANNOUNCE;
break;
STATE = BATTERY_ANNOUNCE;
break;
}
}
if (rx_frame.MsgID == 0x1871 && rx_frame.data.u64 == __builtin_bswap64(0x0500010000000000)) {
CAN_WriteFrame(&SOLAX_1881);
CAN_WriteFrame(&SOLAX_1882);
Serial.println("1871 05-frame received from inverter");
}
if (rx_frame.MsgID == 0x1871 && rx_frame.data.u8[0] == (0x03)) {
Serial.println("1871 03-frame received from inverter");
Serial.println("1871 03-frame received from inverter");
}
}

View file

@ -1,9 +1,9 @@
#ifndef SOLAX_CAN_H
#define SOLAX_CAN_H
#include <Arduino.h>
#include "../../USER_SETTINGS.h"
#include "../devboard/can/ESP32CAN.h"
#include "../devboard/config.h"
#include "../../USER_SETTINGS.h"
#include "../lib/pierremolinaro-acan2515/ACAN2515.h"
extern ACAN2515 can;
@ -40,4 +40,4 @@ extern uint8_t inverterAllowsContactorClosing;
void update_values_can_solax();
void receive_can_solax(CAN_frame_t rx_frame);
#endif
#endif